Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS-288: ROS2 crashes when standby mode is set and then set to normal [HUMBLE] #293

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading