Skip to content

How to Write a ROS Package

Zachary Taylor edited this page Sep 27, 2018 · 2 revisions

...that Helen doesn't hate.

This tutorial will cover the basics of using ROS within the MAV team, how to make a package, what your files should look like, and what the configuration parameters and inputs/outputs should be.

Table of Contents

Chapter 1: ROS Package

package.xml

Use package format 2.0, which removes the distinction between <run_depend> and <build_depend> and makes this more compact.

Use spaces, 2-wide as indentation.

Example:

<?xml version="1.0"?>
<package format="2">
  <name>mav_local_planner</name>
  <version>0.0.0</version>
  <description>
    Local planner with multiple configurable components for planning
    straight-line paths to waypoints, checking global plans for collisions,
    and doing local obstacle avoidance.
  </description>

  <maintainer email="helenoleynikova@gmail.com">Helen Oleynikova</maintainer>

  <license>BSD</license>

  <buildtool_depend>catkin</buildtool_depend>
  <buildtool_depend>catkin_simple</buildtool_depend>

  <depend>mav_msgs</depend>
  <depend>mav_planning_utils</depend>
  <depend>planner_ompl</depend>
  <depend>planner_base</depend>
  <depend>planning_msgs</depend>
  <depend>roscpp</depend>
  <depend>tf</depend>
</package>

CMakeLists.txt

You should use catkin_simple rather than the old-style catkin lists, since they make everything easier. Use spaces, 2-wide as indentation.

A few tips:

  • catkin_simple(ALL_DEPS_REQUIRED) will make sure that all dependencies in the package.xml above are found on the system and loaded.
  • Make a library called ${PROJECT_NAME} and link any executables against it.
  • If you're outputting messages, this is done automatically by catkin simple. However, if you have executables and messages in the same package (prefer not to do this, just have a whatever_msgs package instead), you need to add this to after your executable/library so that things are built in the right order: add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS})

See the documentation at the link above, and this example:

cmake_minimum_required(VERSION 2.8.3)
project(mav_local_planner)

find_package(catkin_simple REQUIRED)
catkin_simple(ALL_DEPS_REQUIRED)

add_definitions(-std=c++11)

#############
# LIBRARIES #
#############
cs_add_library(${PROJECT_NAME}
  src/trajectory_sampler.cpp
)

############
# BINARIES #
############
cs_add_executable(local_planner_node
  src/local_planner_node.cpp
)
target_link_libraries(local_planner_node ${PROJECT_NAME})

##########
# EXPORT #
##########
cs_install()
cs_export()

Folder/file structure

Your package should look something like the example below. See the ROS Package Documentation for more details.

Keep in mind:

  • Your headers should be in include/PACKAGE_NAME/header.h
  • Your source files should be in the src/ folder.
  • Ideally, if you have ROS parameters in your node, you should have the default values and descriptions in a .yaml file in the cfg folder.
mav_local_planner
├── CMakeLists.txt
├── cfg
│   └── default_local_planner_params.yaml
├── include
│   └── mav_local_planner
│       └── trajectory_sampler.h
├── package.xml
└── src
    ├── local_planner_node.cpp
    └── trajectory_sampler.cpp

Example default_local_planner_params.yaml. Always have units when available!

# This file is meant as an example and explanation of the planning params.
# Everything in the base is for the local planner.
local_planning_horizon: 3 # [sec], how far forward to sample trajectories
trajectory_sampling_dt: 0.01 # [sec], how often to sample the trajectory for the controller.
collision_sampling_dt: 0.1 # [sec], how often to check for collisions along the path.
command_publishing_dt: 1.0 # [sec], how often to publish new commands to position controller.
mpc_prediction_horizon: 30 # [timesteps], how many timesteps ahead to publish in addition to the rate

# What kind of planners, obstacle avoidance, etc. to use.
use_obstacle_avoidance: false
# Whether to publish any new trajectories immediately or wait for start
# service call.
autostart: true

Chapter 2: Node Handles, Parameters, and Topics

Topic naming, node naming, namespacing

First, read the Naming overview on the ROS Wiki, as it will clear up a lot of questions about private/public/relative namespaces. Second, never use global namespaces for topic names.

Why namespaces?

Each of our helicopters runs all its nodes and topics in its own namespace. This makes it easier to see (1) which helicopter something is running on, and (2) makes it possible to run several helicopters at the same time. This is absolutely essential for any collaborative missions with the helicopters, so all nodes have to stick to the namespacing convention.

ROS topic names:

No global names. This is because they do not resolve properly when you push nodes into namespaces, and does not allow you to run more than one of your node at a time properly. Or use multiple robots on the same master. Basically just creates a world of problems.

Good: odometry, binary_map, cam0/camera_info
Bad: /odometry, /binary_map, /helicopter/cam0/camera_info

If you want to use a namespace, prefer to actually namespace the node handle on which the publisher is created.

Node Handles

There are 4 main types of node handles:

  1. Default (public) node handle - nh_ = ros::NodeHandle();
  2. Private node handle - nh_private_ = ros::NodeHandle("~");
  3. Namespaced node handle - nh_aslam_ = ros::NodeHandle("aslam");
  4. Global node handle - nh_global_ = ros::NodeHandle("/"); - you probably shouldn't use this ever.

Generally you will only use the first 2 - you could also use the namespaced node handle for separating out publishers for nodes that have many.

To explain what these do and how they should be used, let's assume your ROS node is named ros_node, in namespace blah, and you are trying to look up the name topic. Here is what they will resolve to using all 3 nodehandles:

  1. /blah/topic
  2. /blah/ros_node/topic
  3. /blah/aslam/topic
  4. /topic

If, instead, your try to resolve /topic, this will skip the namespace of the node and resolve to /topic.

When to use which Node Handle

These are just general guidelines, but when possible, prefer to use the following in each case:

  • Subscribers - usually public node handles.
  • Publishers - usually private node handles for most output/visualization, occasionally necessary to use public for globally-used data (i.e., /odom topic).
  • Parameters - almost always private node handle.

Parameters

If a node (or the underlying libraries) have configurations that can be set at startup, expose them as ROS parameters. Your parameters should be_named_like_this.

It is important to provide reasonable defaults for your params. Prefer to make them member variables in a class, and set them to the correct value in the constructor.

Then you can read new values for them

Chapter 3: Coding Standards

Google C++ Style

We use the Google Style Guide and indent with 2-wide spaces. 80-characters wide. Only exception is that we lead function names with a lower-case letter to distinguish from classes (thisIsMyFunction in our style, vs ThisIsMyFunction in pure Google C++).

Autoformatting

Take some time to set up an autoformatter in your editor. Keep in mind that the eclipse autoformatter does not put brackets in the right place, but does most of the rest.

For extreme cases, use clang-format AND BE VERY CAREFUL TO ONLY RUN THIS ON YOUR OWN PACAKGE.
This will autoformat everything in the package:

sudo apt-get install clang-format-3.4 
find -name "*.cpp" | xargs clang-format-3.4 -style=Google -i
find -name "*.h" | xargs clang-format-3.4 -style=Google -i

Chapter 4: Transformation

Use minkindr to represent transformations.

Further details on the transformation notation, frame names and conventions can be found on the Coordinate Systems wiki page.

Chapter 5: Conversions

My source/sink data is...

Eigen

To to/from messages, use eigen_conversions (or minkindr_conversions below).

Example:

#include <eigen_conversions/eigen_msg.h>

Eigen::Vector3d my_super_cool_vector(1.0, 2.0, 3.0);
geometry_msgs::Point point_msg;
tf::pointEigenToMsg(my_super_cool_vector, point_msg);
super_cool_publisher_.publish(point_msg);

To go to/from TF, use tf_conversions (or also minkindr_conversions below).

Example:

#include <tf_conversions/tf_eigen.h>

Eigen::Vector3d my_super_cool_vector(1.0, 2.0, 3.0);
tf::Vector3 my_super_cool_vector_tf;
tf::vectorEigenToTF(my_super_cool_vector, my_super_cool_vector_tf);
tf::Transform transform;
transform.setOrigin(my_super_cool_vector_tf);
transform_broadcaster_.sendTransform(
    tf::StampedTransform(transform, ros::Time::now(), "map", "world"));

minkindr (aslam::Transformation)

Please use the minkindr_conversions package in the minkindr_ros repo. This also wraps some of the Eigen/TF conversions for common datatypes (Eigen::Quaterniond, Eigen::Vector3d), so it is a viable alternative to {tf,eigen}_conversions in most cases. It also transforms minkindr Transformations back and forth to both messages and TF.

Example:

#include <minkindr_conversions/kindr_msg.h>
#include <minkindr_conversions/kindr_tf.h>

Eigen::Quaterniond rotation(Eigen::Vector4d::Random());
rotation.normalize();
Eigen::Vector3d position(Eigen::Vector3d::Random());
kindr::minimal::QuatTransformation kindr_transform(rotation, position);

geometry_msgs::Pose msg;
tf::poseKindrToMsg(kindr_transform, &msg);
publisher_.publish(msg);

tf::Transform tf_transform;
tf::transformKindrToTF(kindr_transform, &tf_transform);
transform_broadcaster_.sendTransform(
    tf::StampedTransform(tf_transform, ros::Time::now(), "map", "world"));

openCV Image

Please use cv_bridge. This allows very easy conversions to/from ROS messages.

Example:

#include <cv_bridge/cv_bridge.h>

const stereo_msgs::DisparityImageConstPtr& msg;  // We got this from a subscription callback.
cv::Mat output_image;
cv_bridge::CvImageConstPtr cv_img_ptr = cv_bridge::toCvShare(msg->image, msg);
// This is a shallow copy.
output_image = cv_img_ptr->image;

cv_bridge::CvImage image_cv_bridge;
image_cv_bridge.header.frame_id = "map";
image_cv_bridge.image = output_image;
publisher_.publish(image_cv_bridge.toImageMsg());