## page was copied from ROS/Tutorials/rosbuild/CreatingPackage
<<TOC(4)>>

== Using roscreate ==
Before we create a package, let's see how the `roscreate-pkg` command-line tool works. This creates a new ROS [[Packages|package]].  All ROS packages consist of the many similar files : [[Manifest|manifests]], [[CMakeLists|CMakeLists.txt]], mainpage.dox, and Makefiles.   roscreate-pkg eliminates many tedious tasks of creating a new package by hand, and eliminates common errors caused by hand-typing build files and manifests. 

To create a new package in the current directory:

{{{
# roscreate-pkg [package_name]
}}}

You can also specify dependencies of that package:

{{{
# roscreate-pkg [package_name] [depend1] [depend2] [depend3]
}}}

== Creating a New ROS Package ==
Now we're going to go into your home or project directory and create our {{{beginner_tutorials}}} package. We are going to make it depend on [[std_msgs]], [[roscpp]], and [[rospy]], which are common ROS packages.

Now go into the ~/fuerte_workspace/sandbox directory:
{{{
$ cd ~/fuerte_workspace/sandbox
}}}
Alternatively, if you use Fuerte or later release, you can simply do:
{{{
$ roscd
$ cd sandbox
}}}

Then create your package:
{{{
$ roscreate-pkg beginner_tutorials std_msgs rospy roscpp
}}}

You will see something similar to:
 {{{
Creating package directory ~/fuerte_workspace/sandbox/beginner_tutorials
Creating include directory ~/fuerte_workspace/sandbox/beginner_tutorials/include/beginner_tutorials
Creating cpp source directory ~/ros/ros_tutorials/beginner_tutorials/src
Creating python source directory ~/fuerte_workspace/sandbox/beginner_tutorials/src/beginner_tutorials
Creating package file ~/fuerte_workspace/sandbox/beginner_tutorials/Makefile
Creating package file ~/fuerte_workspace/sandbox/beginner_tutorials/manifest.xml
Creating package file ~/fuerte_workspace/sandbox/beginner_tutorials/CMakeLists.txt
Creating package file ~/fuerte_workspace/sandbox/beginner_tutorials/mainpage.dox

Please edit beginner_tutorials/manifest.xml and mainpage.dox to finish creating your package

}}}

You're going to want to spend some time looking at `beginner_tutorials/manifest.xml`. [[Manifest|manifests]] play an important role in ROS as they define how Packages are built, run, and documented. 

Now lets make sure that ROS can find your new package. It is often useful to call ''rospack profile'' after making changes to your path so that new directories will be found:

{{{
$ rospack profile
$ rospack find beginner_tutorials 
}}}
 {{{
YOUR_PACKAGE_PATH/beginner_tutorials
}}}

If this fails, it means ROS can't find your new package, which may be an issue with your `ROS_PACKAGE_PATH`. Please consult the installation instructions for setup from SVN or from binaries, depending how you installed ROS. If you've created or added a package that's outside of the existing package paths, you will need to amend your [[ROS/EnvironmentVariables#ROS_PACKAGE_PATH|ROS_PACKAGE_PATH]] environment variable to include that new location. Try re-sourcing your setup.sh in your fuerte_workspace.

Try moving to the directory for the package.
{{{
$ roscd beginner_tutorials 
$ pwd
}}}
 {{{
YOUR_PACKAGE_PATH/beginner_tutorials
}}}

== First-order package dependencies ==
When using {{{roscreate-pkg}}} earlier, a few package dependencies were provided. 
These '''first-order''' dependencies can now be reviewed with the {{{rospack}}} tool.

{{{#!wiki blue/solid
(Jan 9, 2013) There is [[https://github.com/ros/rospack/issues/4|a bug]] reported and already fixed in [[rospack]] in `groovy`; it may take some time to be reflected in the packages. If you see [[http://answers.ros.org/question/51555/beginner-tutorials-segmentation-fault-with-rospack-depends1/?comment=51762#comment-51762|an issue similar to this]] with the next command, you can skip to the following command.
}}}

{{{
$ rospack depends1 beginner_tutorials 
}}}
 {{{
std_msgs
rospy
roscpp
}}}

As you can see, {{{rospack}}} lists the same dependencies that were used as arguments when running {{{roscreate-pkg}}}. 
These dependencies for a package are stored in the '''manifest''' file.  Take a look at the manifest file.

{{{ 
$ roscd beginner_tutorials
$ cat manifest.xml
}}}
 {{{
<package>

...

  <depend package="std_msgs"/>
  <depend package="rospy"/>
  <depend package="roscpp"/>

</package>
}}}

== Indirect package dependencies ==
In many cases, a dependency will also have its own dependencies.  For instance, `rospy` has other dependencies.

{{{#!wiki blue/solid
(Jan 9, 2013) There is [[https://github.com/ros/rospack/issues/4|a bug]] reported and already fixed in [[rospack]] in `groovy`; it may take some time to be reflected in the packages. If you see [[http://answers.ros.org/question/51555/beginner-tutorials-segmentation-fault-with-rospack-depends1/?comment=51762#comment-51762|an issue similar to this]] with the next command, you can skip to the following command.
}}}

{{{
$ rospack depends1 rospy
}}}
 {{{
roslib
roslang
}}}

A package can have quite a few indirect dependencies.  Luckily {{{rospack}}} can recursively determine all nested dependencies.
{{{
$ rospack depends beginner_tutorials
}}}
 {{{
rospack
roslib
std_msgs
rosgraph_msgs
rosbuild
roslang
rospy
cpp_common
roscpp_traits
rostime
roscpp_serialization
xmlrpcpp
rosconsole
roscpp
}}}

Note: in Fuerte, the list is much shorter:
 {{{
std_msgs
roslang
rospy
roscpp
}}}

== ROS Client Libraries ==
You may be wondering what {{{rospy}}} and {{{roscpp}}} dependencies are from the previous examples.  {{{rospy}}} and {{{roscpp}}} are [[Client Libraries || ROS Client Libraries]].  The client libraries allow different programming languages to communicate through ROS.  {{{rospy}}} is the client library for Python.  {{{roscpp}}} is the client library for C++. 

== Review ==
Lets just list some of the commands we've used so far:
 * roscreate-pkg = ros+create-pkg : generates all the files needed to create a ROS package
 * rospack = ros+pack(age) : provides information related to ROS packages
 * rosstack = ros+stack  : provides information related to ROS stacks