Robotics StackExchange | Archived questions

zero latency publishing of sensor data

Hi !

I have a sensor producing data at high but variable frequency, i.e. random times between two incoming data point. I have a callback function (independent from ROS) that gets called when there is incoming sensor data. I'd like that function to publish the data into a a ROS topic immediately as it receives with no latency.

I found no example for this, the available examples are using some Node with fixed "spin" rate, that gets called by rclcpp.spin() and checking for already received data that they publish then. However this solution introduces latency on the receiver side, since data could have arrived before the spin()'s callback is called.

Is there an easy way to implement the above functionality in C++ ROS2 Eloquent ?

thanks, G

Asked by gdebrecz on 2019-11-19 12:04:11 UTC

Comments

Have you tried calling the ROS publish function from within your callback?

Asked by Dirk Thomas on 2019-11-19 12:07:50 UTC

I found no examples for that for ROS2. Old examples using ros/ros.h like https://raw.githubusercontent.com/ros/ros_tutorials/kinetic-devel/roscpp_tutorials/talker/talker.cpp seems not working under ros2.

Asked by gdebrecz on 2019-11-19 12:13:54 UTC

Answers

In the meantime I've found the solution on the net in different pieces: It publishes the sensor data immediately as it arrived to the host.

Please find the relevant code chunks below:

// Initializing ROS.
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = 7;
rclcpp::WallRate loop_rate(100);
rclcpp::init(argc, argv);

// Creating a node
auto node            = rclcpp::Node::make_shared("IMU_node");

// Creating a publisher
auto imu_publisher      = node->create_publisher<sensor_msgs::msg::Imu>("Imu_topic", custom_qos_profile.depth);

// Creating the message
auto imu_msg            = std::make_shared<sensor_msgs::msg::Imu>();

while( rclcpp::ok() )
{
    // Listen to the sensor
     std::string buf = imu.SerialReadLine();

     // Interpret buf and derive relevant values and store in  'value';
    .
    .
    .
     // Fill the IMU msg
     imu_msg->orientation.x  = value;
     imu_publisher->publish(*imu_msg);
     rclcpp::spin_some(node);
}

Asked by gdebrecz on 2019-11-22 10:26:09 UTC

Comments