Skip to content

Commit

Permalink
Resolve the issue of losing LaserScans when DUAL mode enabled
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Nov 23, 2023
1 parent 7a0e93f commit 36b80f1
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 8 deletions.
9 changes: 5 additions & 4 deletions ouster-ros/src/laser_scan_processor.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,14 +30,15 @@ class LaserScanProcessor {
ld_mode(info.mode),
ring_(ring),
pixel_shift_by_row(info.format.pixel_shift_by_row),
scan_msgs(get_n_returns(info),
std::make_shared<sensor_msgs::msg::LaserScan>()),
post_processing_fn(func) {}
scan_msgs(get_n_returns(info)), post_processing_fn(func) {
for (size_t i = 0; i < scan_msgs.size(); ++i)
scan_msgs[i] = std::make_shared<sensor_msgs::msg::LaserScan>();
}

private:
void process(const ouster::LidarScan& lidar_scan, uint64_t,
const rclcpp::Time& msg_ts) {
for (int i = 0; i < static_cast<int>(scan_msgs.size()); ++i) {
for (size_t i = 0; i < scan_msgs.size(); ++i) {
*scan_msgs[i] = lidar_scan_to_laser_scan_msg(
lidar_scan, msg_ts, frame, ld_mode, ring_, pixel_shift_by_row, i);
}
Expand Down
3 changes: 1 addition & 2 deletions ouster-ros/src/os_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,7 @@ class OusterCloud : public OusterProcessingNodeBase {
processors.push_back(LaserScanProcessor::create(
info, tf_bcast.lidar_frame_id(), scan_ring,
[this](LaserScanProcessor::OutputType msgs) {
for (size_t i = 0; i < msgs.size(); ++i)
scan_pubs[i]->publish(*msgs[i]);
for (size_t i = 0; i < msgs.size(); ++i) scan_pubs[i]->publish(*msgs[i]);
}));
}

Expand Down
3 changes: 1 addition & 2 deletions ouster-ros/src/os_driver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,8 +126,7 @@ class OusterDriver : public OusterSensor {
processors.push_back(LaserScanProcessor::create(
info, tf_bcast.lidar_frame_id(), scan_ring,
[this](LaserScanProcessor::OutputType msgs) {
for (size_t i = 0; i < msgs.size(); ++i)
scan_pubs[i]->publish(*msgs[i]);
for (size_t i = 0; i < msgs.size(); ++i) scan_pubs[i]->publish(*msgs[i]);
}));
}

Expand Down

0 comments on commit 36b80f1

Please sign in to comment.