Migration Guide for ROS 2 Humble - ok-tmhr/neonavigation GitHub Wiki

Header

-#include <ros/ros.h>
-#include <std_msgs/Bool.h>
-#include <std_srvs/Empty.h>

+#include <rclcpp/rclcpp.hpp>
+#include <std_msgs/msg/bool.hpp>
+#include <std_srvs/srv/empty.hpp>

-#include <trajectory_tracker_msgs/ChangePath.h>
+#include <trajectory_tracker_msgs/srv/change_path.hpp>

Namespace

  • *_msgs:: -> *_msgs::msg::, *_msgs::srv::, or *_msgs::action::
  • *_srvs:: -> *_srvs::srv::
  • ros:: -> rclcpp::
-std_msgs::Bool
-std_srvs::Empty
+std_msgs::msg::Bool
+std_srvs::srv::Empty

-trajectory_tracker_msgs::ChangePath
+trajectory_tracker_msgs::srv::ChangePath
-ros::Time(0)
+rclcpp::Time(0)

-ros::Duration(0)
+rclcpp::Duration(0, 0)

-ros::init(argc, argv, "trajectory_tracker")
+rclcpp::init(argc, argv)

-ROS_INFO("%d", 3)
+RCLCPP_INFO(this->get_logger(), "%d", 3)

ROS Parameter

Parameters should normally be declared first. They are captured by node namespace "~" and are not necessary to be specified it.

-  pnh_.param("frame_robot", frame_robot_, std::string("base_link"));
+  frame_robot_ = this->declare_parameter<std::string>("frame_robot", "base_link");

Note

Namespace has changed its divisor from slash ("/") to dot (".")

Communication

Latch option is available with QoS reliability of transient local.

-pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryTrackerStatus>("status", 10, true);
+pub_status_ = this->create_publisher<trajectory_tracker_msgs::msg::TrajectoryTrackerStatus>("~/status", rclcpp::QoS(10).transient_local());

Caution

Full migration of latch transport requires subscriptions the same policy (transient local) as publisher.

There is not any replacement of ros::TransportHints().tcpNoDelay(true) in ROS 2.

-  sub_path_velocity_ = nh_.subscribe<trajectory_tracker_msgs::PathWithVelocity>(
-      "path_velocity", 2,
-      boost::bind(&TrackerNode::cbPath<trajectory_tracker_msgs::PathWithVelocity>, this, _1));

Timer callback has no arguments.

-  void cbTimer(const ros::TimerEvent&);
+  void cbTimer();

API

tf2::toMsg(const tf2::Quaternion&)

Include tf2_geometry_msgs/tf2_geometry_msgs.hpp

ros

Replace ros::spinOnce with rclcpp::spin_some because rclcpp does not support spin_once.

tf2_ros

tf2_ros provide convenient conversion between tf2 time object and ROS time object.

  • tf2::Duration and rclcpp::Duration / builtin_interfaces::msg::Duration
  • tf2::TimePoint and rclcpp::Time / builtin_interfaces::msg::Time
  • builtin_interfaces::msg::Time to seconds (double)

Tf

include tf2_ros/buffer.h for tf2_ros::Buffer.

tf2_ros::Buffer cannot be initialized by default, so we should make it in node constructor instead of initializer list.

-tf2_ros::Buffer tfbuf_;
-tf2_ros::TransformListener tfl_;
-tf2_ros::TransformBroadcaster tfb_;
-tf2_ros::StaticTransformBroadcaster tf_static_broadcaster_;

+std::unique_ptr<tf2_ros::Buffer> tfbuf_;
+std::shared_ptr<tf2_ros::TransformListener> tfl_;
+std::unique_ptr<tf2_ros::TransformBroadcaster> tfb_;
+std::unique_ptr<tf2_ros::StaticTransformBroadcaster> tf_static_broadcaster_;

RecorderNode::RecorderNode()
  : rclcpp::Node("trajectory_recorder")
-  , tfl_(tfbuf_)
{

+  tfbuf_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
+  tfl_ = std::make_shared<tf2_ros::TransformListener>(*tfbuf_);
+  tfb_= std::make_unique<tf2_ros::TransformBroadcaster>(*this);
+  tf_static_broadcaster_ = std::make_unique<tf2_ros::StaticTransformBroadcaster>(this);

}

Objects

ros::NodeHandle has been replaced with rclcpp::Node

-class RecorderNode
+class RecorderNode : public rclcpp::Node
{

-  ros::NodeHandle nh_;
-  ros::NodeHandle pnh_;

RecorderNode::RecorderNode()
-  : nh_()
-  , pnh_("~")
+  : rclcpp::Node("trajectory_recorder")
}

Smart Pointer

Publishers, subscriptions, nodes, and etc are defined as shared pointers.

-ros::ServiceServer srs_clear_path_;
-ros::Publisher pub_path_;

rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr pub_path_;
int main(int argc, char** argv)
{
-  ros::init(argc, argv, "trajectory_recorder");
+  rclcpp::init(argc, argv);

-  RecorderNode rec;
-  rec.spin();

+  auto rec = std::make_shared<RecorderNode>();
+  rec->spin();

  return 0;
}

Note that a node name is passed to node constructor instead of ros::init.

A spin function receives node as a shared pointer.

-ros::spinOnce();
+rclcpp::spin_some(shared_from_this());

Note

shared_from_this() is valid only in the scope of Node class. Otherwise, pass node instance created by std::make_shared.

Service

Service server callback has changed its signature and return type.

-  bool clearPath(std_srvs::Empty::Request& req,
-                 std_srvs::Empty::Response& res);
+  void clearPath(std_srvs::srv::Empty::Request::SharedPtr req,
+                 std_srvs::srv::Empty::Response::SharedPtr res);

Time

Use this->now() instead of ros::Time::now(), and rclcpp::Clock::now instead of ros::WallTime::now.

rclcpp::Clock clock;
clock.now();

rclcpp::Duration does not have constructor for a floating value. Use rclcpp::Duration::from_seconds instead.

-ros::Duration(0.2)
+rclcpp::Duration::from_seconds(0.2)

Initialize rclcpp::Timer member with RCL_ROS_TIME because it initialize with clock type by default, RCL_SYSTEM_TIME, while node clock referred by this->get_clock() has RCL_ROS_TIME. Time with different clock type cannot operate and it will raise runtime error like:

rclcpp::Time prev_odom_stamp_;
rclcpp::Duration time_elapsed = this->get_clock()->now() - prev_odom_stamp_;

// -> std::runtime_error' what(): can't subtract times with different time sources

Do initialize with RCL_ROS_TIME as following:

TrackerNode::TrackerNode()
  : rclcpp::Node("trajectory_tracker")
  , is_path_updated_(false)
  , prev_odom_stamp_(0LL, RCL_ROS_TIME)
{

}

The default clock type differs by use cases:

  • RCL_ROS_TIME
    • rclcpp::Time(builtin_interfaces::msg::Time)
    • rclcpp::Time::operator=(builtin_interfaces::msg::Time) when rclcpp::Time has RCL_ROS_TIME clock type
  • RCL_SYSTEM_TIME
    • rclcpp::Time()
    • rclcpp::Time::operator=(builtin_interfaces::msg::Time) when rclcpp::Time has RCL_SYSTEM_TIME clock type

Comparison must have the same time source as well:

prev_odom_stamp_ != rclcpp::Time() // NG. Right hand may have different time source with the left.
prev_odom_stamp_ != rclcpp::Time(0LL, prev_odom_stamp_.get_clock_type()) // OK. Right hand always has the same time source.

builtin_interfaces::msg::Time has no operator(-) with rclcpp::Time. Use rclcpp::Time::operator-.

-const double dt = std::min(max_dt_, (odom->header.stamp - prev_odom_stamp_).toSec());
+const double dt = std::min(max_dt_, (rclcpp::Time(odom->header.stamp) - prev_odom_stamp_).seconds());

rclcpp::Time has no automatic conversion to string. Use rclcpp::Time::seconds as

-ROS_WARN_STREAM("Odometry timeout. Last odometry stamp: " << prev_odom_stamp_);
+RCLCPP_WARN_STREAM(this->get_logger(), "Odometry timeout. Last odometry stamp: " << prev_odom_stamp_.seconds());

ROS 2 does not support Duration::sleep. Replace it with rclcpp::sleep_for

-ros::Duration(0.5).sleep();
+rclcpp::sleep_for(std::chrono::milliseconds(500));

replace ros::Time::isSimTime() with use_sim_time parameter.

-ros::Time::isSimTime() && last_joy_msg_ == ros::Time(0)
+this->get_parameter("use_sim_time").as_bool() && last_joy_msg_ == rclcpp::Time(0LL, RCL_ROS_TIME)

Timer

Timer object cannot stop or change period in ROS 2, so cancel or recreate it.

-    if (odom_timeout_timer_.isValid())
-    {
-      odom_timeout_timer_.setPeriod(ros::Duration(odom_timeout_sec_), true);
-    }
-    else
-    {
-      odom_timeout_timer_ =
-          nh_.createTimer(ros::Duration(odom_timeout_sec_), &TrackerNode::cbOdomTimeout, this, true, true);
-    }
+      odom_timeout_timer_ = this->create_wall_timer(
+        std::chrono::duration<double>(odom_timeout_sec_),
+        std::bind(&TrackerNode::cbOdomTimeout, this));

Note

create_wall_timer cannot receive Duration instance, so convert it into std::chrono::duration

In addition, ROS 2 timer always starts automatically and does not support for one-shot event. Instead, call cancel method properly.

Logging

Replace macros with RCLCPP_* and use a named logger linked to node instance.

-ROS_WARN("TF exception: %s", e.what());
+RCLCPP_WARN(this->get_logger(), "TF exception: %s", e.what());

Throttle logging has changed the unit of time period from seconds to milliseconds.

-ROS_ERROR_THROTTLE(1.0, "path_velocity.velocity.x must be positive");
+RCLCPP_ERROR_THROTTLE(this->get_logger(), *this->get_clock(), 1000, "path_velocity.velocity.x must be positive");

Interface

std_msgs::Header no longer has a seq field.

Serialization

ROS 1 serializes a message with ros::serialization and boost::shared_array:

void SaverNode::cbPath(const nav_msgs::Path::ConstPtr& msg)
{
  std::ofstream ofs(filename_.c_str());

  uint32_t serial_size = ros::serialization::serializationLength(*msg);
  ROS_INFO("Size: %d\n", (int)serial_size);
  boost::shared_array<uint8_t> buffer(new uint8_t[serial_size]);

  ros::serialization::OStream stream(buffer.get(), serial_size);
  ros::serialization::serialize(stream, *msg);

  ofs.write(reinterpret_cast<char*>(buffer.get()), serial_size);
}

ROS 2 does it with serialization and serialized message.

#include <rclcpp/serialization.hpp>
#include <rclcpp/serialized_message.hpp>

void SaverNode::cbPath(const nav_msgs::msg::Path::ConstPtr& msg)
{
  std::ofstream ofs(filename_.c_str());

  auto serialized_msg = std::make_shared<rclcpp::SerializedMessage>();
  rclcpp::Serialization<nav_msgs::msg::Path> serializer;
  serializer.serialize_message(msg.get(), serialized_msg.get());

  RCLCPP_INFO(this->get_logger(), "Size: %d\n", (int)serialized_msg->size());

  ofs.write(reinterpret_cast<char*>(serialized_msg->get_rcl_serialized_message().buffer), serialized_msg->size());
}

As well as deserialization:

for ROS 1,

    ros::serialization::IStream stream(buffer_.get(), serial_size_);
    ros::serialization::deserialize(stream, path_);

and for ROS 2,

    rclcpp::SerializedMessage serialized_msg(serial_size_);
    std::memcpy(serialized_msg.get_rcl_serialized_message().buffer, buffer_.data(), serial_size_);
    rclcpp::Serialization<nav_msgs::msg::Path> serializer;
    serializer.deserialize_message(&serialized_msg, &path_);

Library

Replace boost library with std library.

-boost::shared_array<uint8_t>
+std::vector<uint8_t>

+using std::placeholders::_1;
-srv_im_fb_.insert(mark, boost::bind(&ServerNode::processFeedback, this, _1));
+srv_im_fb_->insert(mark, std::bind(&ServerNode::processFeedback, this, _1));

Dynamic reconfigure

ROS 2 does not support dynamic reconfigure server. Instead, use rclcpp::ParameterEventHandler. See documentation.

Metadata

ROS 1 ROS 2
catkin ament_cmake
roscpp rclcpp
roslint ament_lint_auto, ament_lint_common
rostest ament_cmake_gtest

package.xml

  • upgrade version
  • update maintainer
  • upgrade package format to 3 in case of interface package, required by <member_of_group>
  • export build type ament_cmake for other packages (not mandatory)
+  <export>
+    <build_type>ament_cmake</build_type>
+  </export>

CMakeLists.txt

ament_cmake must install additional directory explicitly, while catkin automatically install package directories.

You want to install launch, config, test data, etc.

install(DIRECTORY data
  DESTINATION share/${PROJECT_NAME}/test
)

Tests

Replace <test> with <executable>

-  <test test-name="test_map_organizer" pkg="map_organizer" type="test_map_organizer">
-    <param name="file_prefix" value="$(arg tmpfile_prefix)" />
-  </test>
+  <executable name="test_map_organizer" cmd="./build/map_organizer/test/test_map_organizer --ros-args -p file_prefix:=$(var tmpfile_prefix)" output="screen">
+  </executable>

ROS 2 does not support rostest. Use gtest and ros2 launch

-add_rostest_gtest(test_map_organizer
-  test/map_organizer_rostest.test
+ament_add_gtest(test_map_organizer
  src/test_map_organizer.cpp
)

Launch

Launch files has changed its format in .xml as following:

  • Namespace has moved from <group> to <node> as namespace attribute
  • Use exec instead of type in <node>
  • Replace arg substitution with var
-  <group ns="saved">
-    <node pkg="map_organizer" type="tie_maps" name="tie_maps2" output="screen" respawn="true">
+  <group>
+    <node pkg="map_organizer" exec="tie_maps" name="tie_maps2" output="screen" respawn="true" namespace="saved">
      <param name="map_files"
-        value="$(arg tmpfile_prefix)0.yaml,$(arg tmpfile_prefix)1.yaml" />
+        value="$(var tmpfile_prefix)0.yaml,$(var tmpfile_prefix)1.yaml" />
      <param name="frame_id" value="map_ground" />
    </node>
  </group>

-  <node pkg="map_organizer" type="select_map" name="select_map" output="screen" />
+  <node pkg="map_organizer" exec="select_map" name="select_map" output="screen" />
⚠️ **GitHub.com Fallback** ⚠️