Packages
The packages object gives you access to metadata about your installed ROS packages. Each of the Package objects has a variety of useful information, similar to what you might find with the rospack command. The API of the Package object is described below.
package.depends1
- Immediate dependencies of the package.
package.manifest
Manifest information from package. This is roslib.manifest.Manifest object.
package.msg
Msgs within package. package_name.msg is equivalent to msg.package_name. You can use this to instantiate msg types, e.g.
packages.std_msgs.msg.Bool()
package.srv
Srvs within package. package_name.srv is equivalent to srv.package_name. You can use this to instantiate srv types.
packages.std_srvs.srv.Empty()
package.path
- Filesystem location of where package is located.
package.nodes
Executable nodes within the package. Nodes can be run using the launch function:
launch(packages.face_detector.nodes.face_detector)
- or by calling them:
packages.face_detector.nodes.face_detector()
- Topics can be remapped for nodes using keyword arguments:
packages.image_view.nodes.image_view(image='webcam/image_raw')
packages.launches
Launch files within the package. Launch files can be run using the launch function:
launch(packages.face_detector.launches.face_detector_rgbd_launch)
Example
In [1]: packages.rospy.depends1.roslib.manifest.license Out[1]: u'BSD'
Stacks
The stacks object gives you access to metadata about your installed ROS stacks. Each of the Stack objects has a variety of useful information, similar to what you might find with the rosstack command. The API of the Stack object is described below.
stack.packages
- Packages within stack.
stack.depends1
- Immediate dependencies of the stack.
stack.manifest
Manifest information from stack. This is roslib.manifest.Manifest object.
stack.path
- Filesystem location of where stack is located.
Example
In [1]: stacks.visualization.depends1.geometry.path Out[1]: '/Users/kwc/ros-pkg/geometry' In [3]: stacks.visualization.packages.rviz.depends1.tf.name Out[3]: 'tf'