ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

ROS 2 zero copy intraprocess communication

asked 2021-06-09 13:13:20 -0500

mschickler gravatar image

I've written a program to measure the latency of communication between separate ROS 2 foxy publisher and a subscriber nodes running in a single process. I'm dynamically allocating memory for the message using make_unique() and passing to publish(). My understanding was that this would result in zero-copy communication to the subscriber. However, the latency seems high and the memory address of the underlying message at the subscriber is different than the address of the originally allocated message. A similar test using shared pointer publish with nodelets in ROS 1 shows the memory address is unchanged at the receiver (i.e. zero-copy occurred).

My code is at: https://github.com/mschickler/simple_...

Any help or insight appreciated.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2021-06-10 06:07:31 -0500

sgvandijk gravatar image

You have to enable intraprocess communication explicitly to have it kick in. You do this with the NodeOptions passed to the nodes. Try the following in combined_node.cpp:

int main(int argc, char** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::executors::MultiThreadedExecutor executor;
  auto intra_comms_options = rclcpp::NodeOptions{}.use_intra_process_comms(true);
  auto probe = std::make_shared<simple_perf_test::ProbeComponent>(intra_comms_options);
  auto target = std::make_shared<simple_perf_test::TargetComponent>(intra_comms_options);
  executor.add_node(probe);
  executor.add_node(target);
  executor.spin();
  rclcpp::shutdown();
  return 0;
}
edit flag offensive delete link more

Comments

Thanks! It worked. I am a little surprised that it still looks like there is about 100-200 microseconds of latency while running in my environment, but at least the addresses now match!

mschickler gravatar image mschickler  ( 2021-06-10 06:41:16 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2021-06-09 13:13:20 -0500

Seen: 486 times

Last updated: Jun 10 '21