Skip to content

Commit

Permalink
address an issue where LaserScan appeared different on FW prior to 2.4
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Nov 23, 2023
1 parent 3a69eb2 commit f903e15
Show file tree
Hide file tree
Showing 4 changed files with 40 additions and 8 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ Changelog
[unreleased]
============
* [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


Expand Down
1 change: 1 addition & 0 deletions ouster-ros/include/ouster_ros/os_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,7 @@ inline bool check_token(const std::set<std::string>& tokens,
return tokens.find(token) != tokens.end();
}

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

} // namespace impl

Expand Down
24 changes: 17 additions & 7 deletions ouster-ros/src/laser_scan_processor.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@

#pragma once

// prevent clang-format from altering the location of "ouster_ros/ros.h", the
// prevent clang-format from altering the location of "ouster_ros/os_ros.h", the
// header file needs to be the first include due to PCL_NO_PRECOMPILE flag
// clang-format off
#include "ouster_ros/os_ros.h"
Expand All @@ -30,17 +30,27 @@ class LaserScanProcessor {
ld_mode(info.mode),
ring_(ring),
pixel_shift_by_row(info.format.pixel_shift_by_row),
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>();
}
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>();

const auto fw = impl::parse_version(info.fw_rev);
if (fw.major == 2 && fw.minor < 4) {
std::transform(pixel_shift_by_row.begin(),
pixel_shift_by_row.end(),
pixel_shift_by_row.begin(),
[](auto c) { return c - 31; });
}
}

private:
void process(const ouster::LidarScan& lidar_scan, uint64_t,
const rclcpp::Time& msg_ts) {
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);
*scan_msgs[i] =
lidar_scan_to_laser_scan_msg(lidar_scan, msg_ts, frame, ld_mode,
ring_, pixel_shift_by_row, i);
}

if (post_processing_fn) post_processing_fn(scan_msgs);
Expand Down
22 changes: 21 additions & 1 deletion ouster-ros/src/os_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,15 @@
#include <chrono>
#include <string>
#include <vector>
#include <regex>


namespace ouster_ros {

namespace sensor = ouster::sensor;
using namespace ouster::util;
using ouster_sensor_msgs::msg::PacketMsg;

namespace ouster_ros {

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

version parse_version(const std::string& fw_rev) {
auto rgx = std::regex(R"(v(\d+).(\d+)\.(\d+))");
std::smatch matches;
std::regex_search(fw_rev, matches, rgx);

if (matches.size() < 4) return invalid_version;

try {
return version{static_cast<uint16_t>(stoul(matches[1])),
static_cast<uint16_t>(stoul(matches[2])),
static_cast<uint16_t>(stoul(matches[3]))};
} catch (const std::exception&) {
return invalid_version;
}
}

} // namespace impl

geometry_msgs::msg::TransformStamped transform_to_tf_msg(
Expand Down

0 comments on commit f903e15

Please sign in to comment.