Skip to content

Commit

Permalink
Use timeout when waiting for packets to be proceed in case they don't…
Browse files Browse the repository at this point in the history
… come (#293)
  • Loading branch information
Samahu committed Feb 9, 2024
1 parent 66d6b9f commit 11287a9
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 8 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ Changelog
* [BUGFIX]: LaserScan is not properly aligned with generated point cloud
* address an issue where LaserScan appeared different on FW prior to 2.4
* [BUGFIX]: LaserScan does not work when using dual mode
* [BUGFIX]: ROS2 crashes when standby mode is set and then set to normal


ouster_ros v0.12.0
Expand Down
2 changes: 1 addition & 1 deletion ouster-ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ouster_ros</name>
<version>0.12.1</version>
<version>0.12.2</version>
<description>Ouster ROS2 driver</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license file="LICENSE">BSD</license>
Expand Down
12 changes: 6 additions & 6 deletions ouster-ros/src/os_sensor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -799,19 +799,19 @@ void OusterSensor::start_packet_processing_threads() {
imu_packets_processing_thread_active = true;
imu_packets_processing_thread = std::make_unique<std::thread>([this]() {
while (imu_packets_processing_thread_active) {
imu_packets->read([this](const uint8_t* buffer) {
on_imu_packet_msg(buffer);
});
imu_packets->read_timeout([this](const uint8_t* buffer) {
if (buffer != nullptr) on_imu_packet_msg(buffer);
}, 1s);
}
RCLCPP_DEBUG(get_logger(), "imu_packets_processing_thread done.");
});

lidar_packets_processing_thread_active = true;
lidar_packets_processing_thread = std::make_unique<std::thread>([this]() {
while (lidar_packets_processing_thread_active) {
lidar_packets->read([this](const uint8_t* buffer) {
on_lidar_packet_msg(buffer);
});
lidar_packets->read_timeout([this](const uint8_t* buffer) {
if (buffer != nullptr) on_lidar_packet_msg(buffer);
}, 1s);
}
RCLCPP_DEBUG(get_logger(), "lidar_packets_processing_thread done.");
});
Expand Down
2 changes: 1 addition & 1 deletion ouster-sensor-msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ouster_sensor_msgs</name>
<version>0.12.0</version>
<version>0.12.2</version>
<description>ouster_ros message and service definitions</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license>BSD</license>
Expand Down

0 comments on commit 11287a9

Please sign in to comment.