ros2
ros2 copied to clipboard
subscribe callback function sometimes block for a long time
trafficstars
Bug report
Required Info:
- Operating System:
- Ubuntu 22.04 (docker)
- Installation type:
- binaries
- DDS implementation:
- Fast-RTPS
- Client library (if applicable):
- rclcpp
Steps to reproduce issue
#include "rclcpp/rclcpp.hpp"
#include <ctime>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <functional>
#include <memory>
#include <chrono>
double last_front_tstamp = 0.0;
double last_rear_tstamp = 0.0;
double last_left_tstamp = 0.0;
double last_right_tstamp = 0.0;
long getCurrentTime()
{
std::chrono::milliseconds ms = std::chrono::duration_cast< std::chrono::milliseconds >(
std::chrono::system_clock::now().time_since_epoch());
return ms.count();
}
using namespace std;
class DemoSubscriber : public rclcpp::Node
{
public:
explicit DemoSubscriber(const string& name)
: Node(name)
{
/*sub_pcloud_center_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/sensor/lidar_center/pcloud_raw",
1,
[this](sensor_msgs::msg::PointCloud2::SharedPtr msg) {
cout << "Center time interval: " << getCurrentTime()-last_center_tstamp << endl;
last_center_tstamp = getCurrentTime();
}
);*/
sub_pcloud_front_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/sensor/rslidar_front/pcloud_distortion",
10,
[this](sensor_msgs::msg::PointCloud2::SharedPtr msg) {
int diff = getCurrentTime()-last_front_tstamp;
if (diff > 300 )
cout << "front time interval: " << diff << endl;
last_front_tstamp = getCurrentTime();
}
);
sub_pcloud_rear_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/sensor/rslidar_rear/pcloud_distortion",
10,
[this](sensor_msgs::msg::PointCloud2::SharedPtr msg) {
int diff = getCurrentTime()-last_rear_tstamp;
if (diff > 300 )
cout << "rear time interval: " << diff << endl;
last_rear_tstamp = getCurrentTime();
}
);
sub_pcloud_left_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/sensor/rslidar_left/pcloud_distortion",
10,
[this](sensor_msgs::msg::PointCloud2::SharedPtr msg) {
int diff = getCurrentTime()-last_left_tstamp;
if (diff > 300)
cout << "left time interval: " << diff << endl;
last_left_tstamp = getCurrentTime();
}
);
sub_pcloud_right_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/sensor/rslidar_right/pcloud_distortion",
10,
[this](sensor_msgs::msg::PointCloud2::SharedPtr msg) {
int diff = getCurrentTime()-last_right_tstamp;
if (diff > 300)
cout << "right time interval: " << diff << endl;
last_right_tstamp = getCurrentTime();
}
);
}
private:
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_pcloud_center_;
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_pcloud_front_;
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_pcloud_rear_;
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_pcloud_right_;
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_pcloud_left_;
};
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(make_shared<DemoSubscriber>("subscriber_node"));
rclcpp::shutdown();
return 0;
}
Expected behavior
There should no print.
Actual behavior
#### Additional information
Four lidar topic steady ~ 10Hz
----
@RainingJoe thanks for creating issue. I got some questions,
- What platform do you use and reproduce this issue? (not docker, but host system CPU and platform information would be appreciated)
- system clock has never been changed during the test? e.g) ntp system time adjustment. i would use steady clock for this kind of test.
- Can you try MultiThreadedExecutor to see if the problem can be solved?