Skip to content

Commit 66d6b9f

Browse files
authored
ROS-196: laser scan from ros driver is not properly aligned with point cloud [humble] (#203)
* Apply destagger to laser scan + Add laser to RVIZ * Align LaserScan with the PointCloud * Apply proper pixel shift * Resolve the issue of zeroed laserscan on dual mode * Address an issue where LaserScan appeared different on FW prior to 2.4 * Fix the issue for odd numbers * List selected sensors on the main page + Update RVIZ config to highlight the 2D LaserScan.
1 parent 726b0d5 commit 66d6b9f

File tree

10 files changed

+124
-30
lines changed

10 files changed

+124
-30
lines changed

CHANGELOG.rst

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,13 @@
22
Changelog
33
=========
44

5+
[unreleased]
6+
============
7+
* [BUGFIX]: LaserScan is not properly aligned with generated point cloud
8+
* address an issue where LaserScan appeared different on FW prior to 2.4
9+
* [BUGFIX]: LaserScan does not work when using dual mode
10+
11+
512
ouster_ros v0.12.0
613
==================
714
* [BREAKING]: updated ouster_client to the release of ``20231031`` [v0.10.0]; changes listed below.

README.md

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
- [Official ROS driver for Ouster sensors](#official-ros-driver-for-ouster-sensors)
1616
- [Overview](#overview)
17+
- [Supported Devices](#supported-devices)
1718
- [Requirements](#requirements)
1819
- [Linux](#linux)
1920
- [Windows](#windows)
@@ -43,6 +44,17 @@ messages on the topics of `/ouster/imu` and `/ouster/points`. In the case the us
4344
dual return and it was configured to use this capability, then another topic will published under the
4445
name `/ouster/points2` which corresponds to the second point cloud.
4546

47+
48+
## Supported Devices
49+
The driver supports the following list of Ouster sensors:
50+
- [OS0](https://ouster.com/products/hardware/os0-lidar-sensor)
51+
- [OS1](https://ouster.com/products/hardware/os1-lidar-sensor)
52+
- [OS2](https://ouster.com/products/hardware/os2-lidar-sensor)
53+
- [OSDome](https://ouster.com/products/hardware/osdome-lidar-sensor)
54+
55+
You can obtain detailed specs sheet about the sensors and obtain updated FW through the website
56+
[downloads](https://ouster.com/downloads) section.
57+
4658
## Requirements
4759
This branch is only intended for use with **Rolling**, **Humble** and **Iron** ROS 2 distros. Please
4860
refer to ROS 2 online documentation on how to setup ROS on your machine before proceeding with the

ouster-ros/config/viz.rviz

Lines changed: 45 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,9 @@ Panels:
1313
- /nearir1/Topic1
1414
- /reflec1
1515
- /signal1
16-
Splitter Ratio: 0.5
16+
- /LaserScan1
17+
- /LaserScan1/Topic1
18+
Splitter Ratio: 0.626074492931366
1719
Tree Height: 1185
1820
- Class: rviz_common/Selection
1921
Name: Selection
@@ -92,23 +94,23 @@ Visualization Manager:
9294
Enabled: true
9395
Frame Timeout: 15
9496
Frames:
95-
" os_imu":
97+
All Enabled: true
98+
os_imu:
9699
Value: true
97-
" os_lidar":
100+
os_lidar:
98101
Value: true
99-
" os_sensor":
102+
os_sensor:
100103
Value: true
101-
All Enabled: true
102104
Marker Scale: 1
103105
Name: TF
104106
Show Arrows: true
105107
Show Axes: true
106108
Show Names: false
107109
Tree:
108-
" os_sensor":
109-
" os_imu":
110+
os_sensor:
111+
os_imu:
110112
{}
111-
" os_lidar":
113+
os_lidar:
112114
{}
113115
Update Interval: 0
114116
Value: true
@@ -168,10 +170,44 @@ Visualization Manager:
168170
Reliability Policy: Best Effort
169171
Value: /ouster/signal_image
170172
Value: true
173+
- Alpha: 1
174+
Autocompute Intensity Bounds: false
175+
Autocompute Value Bounds:
176+
Max Value: 10
177+
Min Value: -10
178+
Value: true
179+
Axis: Z
180+
Channel Name: intensity
181+
Class: rviz_default_plugins/LaserScan
182+
Color: 255; 255; 255
183+
Color Transformer: Intensity
184+
Decay Time: 0
185+
Enabled: true
186+
Invert Rainbow: false
187+
Max Color: 255; 255; 255
188+
Max Intensity: 1000
189+
Min Color: 0; 0; 0
190+
Min Intensity: 0
191+
Name: LaserScan
192+
Position Transformer: XYZ
193+
Selectable: true
194+
Size (Pixels): 3
195+
Size (m): 0.02
196+
Style: Flat Squares
197+
Topic:
198+
Depth: 5
199+
Durability Policy: Volatile
200+
Filter size: 10
201+
History Policy: Keep Last
202+
Reliability Policy: Best Effort
203+
Value: /ouster/scan
204+
Use Fixed Frame: true
205+
Use rainbow: true
206+
Value: true
171207
Enabled: true
172208
Global Options:
173209
Background Color: 48; 48; 48
174-
Fixed Frame: "os_sensor"
210+
Fixed Frame: os_sensor
175211
Frame Rate: 30
176212
Name: root
177213
Tools:

ouster-ros/include/ouster_ros/os_ros.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,14 +108,16 @@ geometry_msgs::msg::TransformStamped transform_to_tf_msg(
108108
* @param[in] frame the parent frame of the generated laser scan message
109109
* @param[in] lidar_mode lidar mode (width x frequency)
110110
* @param[in] ring selected ring to be published
111+
* @param[in] pixel_shift_by_row pixel shifts by row
112+
* @param[in] return_index index of return desired starting at 0
111113
* @return ROS message suitable for publishing as a LaserScan
112114
*/
113115
sensor_msgs::msg::LaserScan lidar_scan_to_laser_scan_msg(
114116
const ouster::LidarScan& ls,
115117
const rclcpp::Time& timestamp,
116118
const std::string &frame,
117119
const ouster::sensor::lidar_mode lidar_mode,
118-
const uint16_t ring,
120+
const uint16_t ring, const std::vector<int>& pixel_shift_by_row,
119121
const int return_index);
120122

121123
namespace impl {
@@ -154,6 +156,7 @@ inline bool check_token(const std::set<std::string>& tokens,
154156
return tokens.find(token) != tokens.end();
155157
}
156158

159+
ouster::util::version parse_version(const std::string& fw_rev);
157160

158161
} // namespace impl
159162

ouster-ros/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>ouster_ros</name>
5-
<version>0.12.0</version>
5+
<version>0.12.1</version>
66
<description>Ouster ROS2 driver</description>
77
<maintainer email="[email protected]">ouster developers</maintainer>
88
<license file="LICENSE">BSD</license>

ouster-ros/src/laser_scan_processor.h

Lines changed: 20 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88

99
#pragma once
1010

11-
// prevent clang-format from altering the location of "ouster_ros/ros.h", the
11+
// prevent clang-format from altering the location of "ouster_ros/os_ros.h", the
1212
// header file needs to be the first include due to PCL_NO_PRECOMPILE flag
1313
// clang-format off
1414
#include "ouster_ros/os_ros.h"
@@ -29,16 +29,28 @@ class LaserScanProcessor {
2929
: frame(frame_id),
3030
ld_mode(info.mode),
3131
ring_(ring),
32-
scan_msgs(get_n_returns(info),
33-
std::make_shared<sensor_msgs::msg::LaserScan>()),
34-
post_processing_fn(func) {}
32+
pixel_shift_by_row(info.format.pixel_shift_by_row),
33+
scan_msgs(get_n_returns(info)),
34+
post_processing_fn(func) {
35+
for (size_t i = 0; i < scan_msgs.size(); ++i)
36+
scan_msgs[i] = std::make_shared<sensor_msgs::msg::LaserScan>();
37+
38+
const auto fw = impl::parse_version(info.fw_rev);
39+
if (fw.major == 2 && fw.minor < 4) {
40+
std::transform(pixel_shift_by_row.begin(),
41+
pixel_shift_by_row.end(),
42+
pixel_shift_by_row.begin(),
43+
[](auto c) { return c - 31; });
44+
}
45+
}
3546

3647
private:
3748
void process(const ouster::LidarScan& lidar_scan, uint64_t,
3849
const rclcpp::Time& msg_ts) {
39-
for (int i = 0; i < static_cast<int>(scan_msgs.size()); ++i) {
40-
*scan_msgs[i] = lidar_scan_to_laser_scan_msg(
41-
lidar_scan, msg_ts, frame, ld_mode, ring_, i);
50+
for (size_t i = 0; i < scan_msgs.size(); ++i) {
51+
*scan_msgs[i] =
52+
lidar_scan_to_laser_scan_msg(lidar_scan, msg_ts, frame, ld_mode,
53+
ring_, pixel_shift_by_row, i);
4254
}
4355

4456
if (post_processing_fn) post_processing_fn(scan_msgs);
@@ -61,6 +73,7 @@ class LaserScanProcessor {
6173
std::string frame;
6274
sensor::lidar_mode ld_mode;
6375
uint16_t ring_;
76+
std::vector<int> pixel_shift_by_row;
6477
OutputType scan_msgs;
6578
PostProcessingFn post_processing_fn;
6679
};

ouster-ros/src/os_cloud_node.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -148,8 +148,7 @@ class OusterCloud : public OusterProcessingNodeBase {
148148
processors.push_back(LaserScanProcessor::create(
149149
info, tf_bcast.lidar_frame_id(), scan_ring,
150150
[this](LaserScanProcessor::OutputType msgs) {
151-
for (size_t i = 0; i < msgs.size(); ++i)
152-
scan_pubs[i]->publish(*msgs[i]);
151+
for (size_t i = 0; i < msgs.size(); ++i) scan_pubs[i]->publish(*msgs[i]);
153152
}));
154153
}
155154

ouster-ros/src/os_driver_node.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ class OusterDriver : public OusterSensor {
4141
}
4242

4343
~OusterDriver() override {
44-
RCLCPP_INFO(get_logger(), "OusterDriver::~OusterDriver() called");
44+
RCLCPP_DEBUG(get_logger(), "OusterDriver::~OusterDriver() called");
4545
halt();
4646
}
4747

@@ -126,8 +126,7 @@ class OusterDriver : public OusterSensor {
126126
processors.push_back(LaserScanProcessor::create(
127127
info, tf_bcast.lidar_frame_id(), scan_ring,
128128
[this](LaserScanProcessor::OutputType msgs) {
129-
for (size_t i = 0; i < msgs.size(); ++i)
130-
scan_pubs[i]->publish(*msgs[i]);
129+
for (size_t i = 0; i < msgs.size(); ++i) scan_pubs[i]->publish(*msgs[i]);
131130
}));
132131
}
133132

ouster-ros/src/os_ros.cpp

Lines changed: 31 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -19,11 +19,15 @@
1919
#include <chrono>
2020
#include <string>
2121
#include <vector>
22+
#include <regex>
23+
24+
25+
namespace ouster_ros {
2226

2327
namespace sensor = ouster::sensor;
28+
using namespace ouster::util;
2429
using ouster_sensor_msgs::msg::PacketMsg;
2530

26-
namespace ouster_ros {
2731

2832
bool is_legacy_lidar_profile(const sensor::sensor_info& info) {
2933
using sensor::UDPProfileLidar;
@@ -130,6 +134,22 @@ std::set<std::string> parse_tokens(const std::string& input, char delim) {
130134
return tokens;
131135
}
132136

137+
version parse_version(const std::string& fw_rev) {
138+
auto rgx = std::regex(R"(v(\d+).(\d+)\.(\d+))");
139+
std::smatch matches;
140+
std::regex_search(fw_rev, matches, rgx);
141+
142+
if (matches.size() < 4) return invalid_version;
143+
144+
try {
145+
return version{static_cast<uint16_t>(stoul(matches[1])),
146+
static_cast<uint16_t>(stoul(matches[2])),
147+
static_cast<uint16_t>(stoul(matches[3]))};
148+
} catch (const std::exception&) {
149+
return invalid_version;
150+
}
151+
}
152+
133153
} // namespace impl
134154

135155
geometry_msgs::msg::TransformStamped transform_to_tf_msg(
@@ -151,7 +171,8 @@ geometry_msgs::msg::TransformStamped transform_to_tf_msg(
151171
sensor_msgs::msg::LaserScan lidar_scan_to_laser_scan_msg(
152172
const ouster::LidarScan& ls, const rclcpp::Time& timestamp,
153173
const std::string& frame, const ouster::sensor::lidar_mode ld_mode,
154-
const uint16_t ring, const int return_index) {
174+
const uint16_t ring, const std::vector<int>& pixel_shift_by_row,
175+
const int return_index) {
155176
sensor_msgs::msg::LaserScan msg;
156177
msg.header.stamp = timestamp;
157178
msg.header.frame_id = frame;
@@ -177,10 +198,14 @@ sensor_msgs::msg::LaserScan lidar_scan_to_laser_scan_msg(
177198
const auto sg = signal.data();
178199
msg.ranges.resize(ls.w);
179200
msg.intensities.resize(ls.w);
180-
int idx = ls.w * ring + ls.w;
181-
for (int i = 0; idx-- > ls.w * ring; ++i) {
182-
msg.ranges[i] = rg[idx] * ouster::sensor::range_unit;
183-
msg.intensities[i] = static_cast<float>(sg[idx]);
201+
202+
uint16_t u = ring;
203+
for (auto v = 0; v < ls.w; ++v) {
204+
auto v_shift = (v + ls.w - pixel_shift_by_row[u] + ls.w / 2) % ls.w;
205+
auto src_idx = u * ls.w + v_shift;
206+
auto tgt_idx = ls.w - 1 - v;
207+
msg.ranges[tgt_idx] = rg[src_idx] * ouster::sensor::range_unit;
208+
msg.intensities[tgt_idx] = static_cast<float>(sg[src_idx]);
184209
}
185210

186211
return msg;

ouster-ros/src/os_sensor_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ OusterSensor::OusterSensor(const rclcpp::NodeOptions& options)
3737
: OusterSensor("os_sensor", options) {}
3838

3939
OusterSensor::~OusterSensor() {
40-
RCLCPP_INFO(get_logger(), "OusterDriver::~OusterSensor() called");
40+
RCLCPP_DEBUG(get_logger(), "OusterSensor::~OusterSensor() called");
4141
halt();
4242
}
4343

0 commit comments

Comments
 (0)