This shouldn’t contain very much... just “anointed” central binaries used by the entire distribution. Most programs (like ROS nodes) will reside in each package’s bin/ directory.
Source directory
e.g. for project ‘proj’:
src/
proj/
CMakeLists.txt
stack.xml # explains interstack dependencies and debian-generating rules
msg/
ProjMsg.msg
srv/
ProjSrv.srv
src/
proj/
__init__.py
othercode.py
libproj/
CMakeLists.txt
proj.cpp
include/
proj/
proj.hpp
otherheaders.hpp
Build directory
build/
env.sh
setup.sh
setup.bash
setup.zsh
etc/
catkin/
profile.d/
00.catkin.buildspace.sh # env hooks. this one is a placeholder added by catkin.
10.ros.buildspace.sh # e.g. the one from ROS
packages.list # mapping from pkg name to subdirectory of build/src dirs, see below
gen/
cpp/ # All generated C++ headers go here.
proj/
ProjMsg.h
ProjSrvRequest.h
ProjSrvResponse.h
py/ # All generated python goes here.
proj/
__init__.py # uses pkgutil to add src/proj/src/ to pythonpath
msg/
__init__.py # generated code
_ProjMsg.py
_ProjSrvRequest.py
_ProjSrvResponse.py
lib/ # all compiled libraries go here
libproj.so
proj/
# the usual cmake-generated stuff.
Makefile
CMakeFiles/
cmake_install.cmake
/opt/ros/fuerte/ # CMAKE_INSTALL_PREFIX
bin/
roscore # possibly some special anointed binaries
rosbag@ # symlink to share/rosbag/bin/rosbag
setup.sh # generated for this environment by catkin
env.sh
lib/
libros.so # shared libraries for all packages
libcpp_common.so
librostime.so
libfoo.a # also static libraries
pythonX.Y/ # python from all packages
rospy/
__init__.py # static code
client.py
core.py
...
std_msgs/
__init__.py # generated code
pkgconfig/ # pkgconfig files are autogenerated
roscpp_serialization.pc
nav_msgs.pc
include/ # all includes, together.
std_msgs/
Float64.h # generated header
ros/
node_handle.h # "static" hand-coded header
time.h
xmlrpc_manager.h
etc/
catkin/
profile.d/
00.catkin.sh
10.ros.sh
ros/
rosinstall.conf # used by rosinstall to set ROS_PACKAGE_PATH
langs/ # to determine which code generators are available.
roscpp # contains "C++"
rospy # contains "Python"
depends.yaml # rosdep main database
depends.d/
00_something.yaml # addons
10_somethingelse.yaml
share/ # During transition, this is also ROS_PACKAGE_PATH
roscpp_tutorials/ # one dir like this per package
manifest.xml # thunk to pkgconfig for transition;
# takes care of exporting to legacy rosmake.
bin/
talker # possibly linked-to from CMAKE_PREFIX_PATH/bin
listener
cmake/ # cmake infrastructure, per-package
roscpp_tutorials-config.cmake
roscpp_tutorials-config-version.cmake
messages.cmake
msg/
Foo.msg
Bar.msg
action/
something.launch # the rest is as the package installs it
stacks/
dry_stack1 # built/installed via rosmake
dry_stack2 # built/installed via rosmake
Contains a mapping of package name to path-to-the-package-relative-to-CATKIN_(BUILD|SOURCE)_DIR, e.g.:
XmlRpc ros_comm/utilities/xmlrpcpp
catkin catkin
cpp_common roscpp_core/cpp_common
gencpp gencpp
genmsg genmsg
genpy genpy
genpybindings genpybindings
geometry_msgs common_msgs/geometry_msgs
nav_msgs common_msgs/nav_msgs
nolangs nolangs
rosconsole ros_comm/tools/rosconsole
roscpp ros_comm/clients/cpp/roscpp
roscpp_serialization roscpp_core/roscpp_serialization
roscpp_traits roscpp_core/roscpp_traits
rosgraph_msgs ros_comm/messages/rosgraph_msgs
roslib ros/core/roslib
rospy ros_comm/clients/rospy
rostime roscpp_core/rostime
sensor_msgs common_msgs/sensor_msgs
std_msgs std_msgs