Skip to content

Commit

Permalink
feat(hesai): implement mask-based pruning filter for Hesai (#251)
Browse files Browse the repository at this point in the history
commit 6e47dbb
Author: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Date:   Mon Feb 17 05:47:57 2025 +0000

    ci(pre-commit): autofix

commit 2931084
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:32:01 2025 +0900

    docs(point_filters): add compatibility table for hesai

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 07ee5bf
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:31:24 2025 +0900

    feat(hesai): add downsample mask filter to decoder

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 3349bdd
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:29:59 2025 +0900

    chore(hesai): add FoV and resolution information to sensor definitions

    Signed-off-by: Max SCHMELLER <[email protected]>

commit ed23f8c
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:29:17 2025 +0900

    chore(hesai): add optional point_filters parameter to schema

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 5400657
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:28:56 2025 +0900

    chore(hesai): add downsample_mask_path config parameter

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 20a5c44
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:27:07 2025 +0900

    chore(nebula_ros): modernize how file extensions are replaced for calibration files

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 4cdc44a
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:18:47 2025 +0900

    chore(hesai_decoders): remove rclcpp logging dependency

    Signed-off-by: Max SCHMELLER <[email protected]>

commit cec2c76
Author: Max SCHMELLER <[email protected]>
Date:   Mon Feb 17 14:32:42 2025 +0900

    chore(angles): introduce `AngleUnit`s, make angle ranges support `end < start`angle.

    Signed-off-by: Max SCHMELLER <[email protected]>

commit a85ea4b
Author: Max SCHMELLER <[email protected]>
Date:   Mon Feb 17 14:31:47 2025 +0900

    chore(downsample_mask): fix imports

    Signed-off-by: Max SCHMELLER <[email protected]>

commit e18ae38
Author: Max SCHMELLER <[email protected]>
Date:   Fri Feb 14 16:46:05 2025 +0900

    fix(downsample_mask): add input validation for constructor parameters

    Add input validation checks for azimuth peak resolution, azimuth range extent, and number of channels to prevent divide-by-zeros and other issues

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 3082e0d
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 15:51:49 2025 +0900

    fix(downsample_mask): make `excluded()` function resilient to rounding errors

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 5655e32
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 15:26:46 2025 +0900

    chore(downsample_mask): explicitly cast instead of implicit conversions

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 1cadf2a
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 15:06:10 2025 +0900

    chore(downsample_mask): remove `.` before the exported mask's suffix

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 8e52dd9
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 15:01:56 2025 +0900

    chore(cspell): add milli-degrees (`mdeg`) to dictionary

    Signed-off-by: Max SCHMELLER <[email protected]>

commit fb6045f
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:15:26 2025 +0900

    docs(downsample_filter): add downsample filter docs

    Signed-off-by: Max SCHMELLER <[email protected]>

commit a14a069
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:10:34 2025 +0900

    test(downsample_mask): add unit tests for dithering and filtering

    Signed-off-by: Max SCHMELLER <[email protected]>

commit e2aed9b
Author: Max SCHMELLER <[email protected]>
Date:   Thu Jan 16 12:08:57 2025 +0900

    chore(downsample_mask): make debug mask output optional, clean up code

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 72aafb3
Author: Max SCHMELLER <[email protected]>
Date:   Wed Jan 15 16:09:32 2025 +0900

    chore(downsample_mask): add dependencies to nebula_decoders/package.xml

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 3c474d7
Author: Max SCHMELLER <[email protected]>
Date:   Wed Jan 15 16:04:19 2025 +0900

    chore(nebula_ros): add schema for point filters, and the downsample mask

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 219b789
Author: Max SCHMELLER <[email protected]>
Date:   Wed Jan 15 16:03:45 2025 +0900

    chore(downsample_mask): add downsample_mask filter class

    The filter takes a path to a PNG image (will be converted to grayscale) and expected resolution/channel count of the mask.

    The grayscale mask is then dithered into a black/white mask of the same dimensions, and an `excluded(NebulaPoint const&)` function is provided to test whether a point shall be excluded according to the mask.

    For debug purposes, the dithered mask is written to the same directory as the input mask, with the file ending changed to `_dithered.png`. If this fails, the filter will not throw but log a warning.

    Signed-off-by: Max SCHMELLER <[email protected]>

commit 65ed6ed
Author: Max SCHMELLER <[email protected]>
Date:   Wed Jan 15 16:03:37 2025 +0900

    chore(nebula_decoders): add utility types for angle pairs, ranges, and FoVs

    Signed-off-by: Max SCHMELLER <[email protected]>

Signed-off-by: Max SCHMELLER <[email protected]>
  • Loading branch information
mojomex committed Feb 18, 2025
1 parent 8efeaf0 commit 74ec71a
Show file tree
Hide file tree
Showing 31 changed files with 146 additions and 71 deletions.
2 changes: 1 addition & 1 deletion docs/filters.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ The following filter types are supported:
| Filter Name | Filter Type | Hesai | Robosense | Velodyne |
| ---------------------- | ----------------- | :---: | :-------: | :------: |
| Downsample Mask Filter | `downsample_mask` | | ❌ | ❌ |
| Downsample Mask Filter | `downsample_mask` | | ❌ | ❌ |
Compatibility:
✅: compatible
Expand Down
4 changes: 3 additions & 1 deletion nebula_common/include/nebula_common/hesai/hesai_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ struct HesaiSensorConfiguration : public LidarConfigurationBase
PtpTransportType ptp_transport_type;
PtpSwitchType ptp_switch_type;
uint8_t ptp_lock_threshold;
std::string downsample_mask_path;
};
/// @brief Convert HesaiSensorConfiguration to string (Overloading the << operator)
/// @param os
Expand All @@ -73,7 +74,8 @@ inline std::ostream & operator<<(std::ostream & os, HesaiSensorConfiguration con
os << "PTP Domain: " << std::to_string(arg.ptp_domain) << '\n';
os << "PTP Transport Type: " << arg.ptp_transport_type << '\n';
os << "PTP Switch Type: " << arg.ptp_switch_type << '\n';
os << "PTP Lock Threshold: " << std::to_string(arg.ptp_lock_threshold);
os << "PTP Lock Threshold: " << std::to_string(arg.ptp_lock_threshold) << '\n';
os << "Downsample Mask Path: " << arg.downsample_mask_path;
return os;
}

Expand Down
2 changes: 2 additions & 0 deletions nebula_decoders/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,12 @@ add_library(nebula_decoders_hesai SHARED
)
target_link_libraries(nebula_decoders_hesai PUBLIC
${pandar_msgs_TARGETS}
${PNG_LIBRARIES}
)

target_include_directories(nebula_decoders_hesai PUBLIC
${pandar_msgs_INCLUDE_DIRS}
${PNG_INCLUDE_DIRS}
)

# Velodyne
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,13 @@
#pragma once

#include "nebula_decoders/nebula_decoders_common/angles.hpp"
#include "nebula_decoders/nebula_decoders_common/point_filters/downsample_mask.hpp"
#include "nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp"
#include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp"
#include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp"

#include <nebula_common/hesai/hesai_common.hpp>
#include <nebula_common/loggers/logger.hpp>
#include <nebula_common/nebula_common.hpp>
#include <nebula_common/point_types.hpp>
#include <rclcpp/logging.hpp>
Expand All @@ -28,7 +30,9 @@
#include <algorithm>
#include <array>
#include <cmath>
#include <cstdint>
#include <memory>
#include <optional>
#include <tuple>
#include <utility>
#include <vector>
Expand All @@ -46,7 +50,7 @@ class HesaiDecoder : public HesaiScanDecoder
float scan_emit_angle;
};

protected:
private:
/// @brief Configuration for this decoder
const std::shared_ptr<const drivers::HesaiSensorConfiguration> sensor_configuration_;

Expand Down Expand Up @@ -74,7 +78,7 @@ class HesaiDecoder : public HesaiScanDecoder
ScanCutAngles scan_cut_angles_;
uint32_t last_azimuth_ = 0;

rclcpp::Logger logger_;
std::shared_ptr<loggers::Logger> logger_;

/// @brief For each channel, its firing offset relative to the block in nanoseconds
std::array<int, SensorT::packet_t::n_channels> channel_firing_offset_ns_;
Expand All @@ -83,15 +87,17 @@ class HesaiDecoder : public HesaiScanDecoder
std::array<std::array<int, SensorT::packet_t::n_blocks>, SensorT::packet_t::max_returns>
block_firing_offset_ns_;

std::optional<point_filters::DownsampleMaskFilter> mask_filter_;

/// @brief Validates and parse PandarPacket. Currently only checks size, not checksums etc.
/// @param packet The incoming PandarPacket
/// @return Whether the packet was parsed successfully
bool parse_packet(const std::vector<uint8_t> & packet)
{
if (packet.size() < sizeof(typename SensorT::packet_t)) {
RCLCPP_ERROR_STREAM(
logger_, "Packet size mismatch: " << packet.size() << " | Expected at least: "
<< sizeof(typename SensorT::packet_t));
NEBULA_LOG_STREAM(
logger_->error, "Packet size mismatch: " << packet.size() << " | Expected at least: "
<< sizeof(typename SensorT::packet_t));
return false;
}
if (std::memcpy(&packet_, packet.data(), sizeof(typename SensorT::packet_t))) {
Expand All @@ -100,7 +106,7 @@ class HesaiDecoder : public HesaiScanDecoder
return true;
}

RCLCPP_ERROR(logger_, "Packet memcopy failed");
logger_->error("Packet memcopy failed");
return false;
}

Expand Down Expand Up @@ -195,7 +201,7 @@ class HesaiDecoder : public HesaiScanDecoder
uint64_t scan_timestamp_ns =
in_current_scan ? decode_scan_timestamp_ns_ : output_scan_timestamp_ns_;

NebulaPoint & point = pc->emplace_back();
NebulaPoint point;
point.distance = distance;
point.intensity = unit.reflectivity;
point.time_stamp = get_point_time_relative(
Expand All @@ -214,6 +220,10 @@ class HesaiDecoder : public HesaiScanDecoder
// The driver wrapper converts to degrees, expects radians
point.azimuth = corrected_angle_data.azimuth_rad;
point.elevation = corrected_angle_data.elevation_rad;

if (!mask_filter_ || !mask_filter_->excluded(point)) {
pc->emplace_back(point);
}
}
}
}
Expand Down Expand Up @@ -246,24 +256,29 @@ class HesaiDecoder : public HesaiScanDecoder
explicit HesaiDecoder(
const std::shared_ptr<const HesaiSensorConfiguration> & sensor_configuration,
const std::shared_ptr<const typename SensorT::angle_corrector_t::correction_data_t> &
correction_data)
correction_data,
const std::shared_ptr<loggers::Logger> & logger)
: sensor_configuration_(sensor_configuration),
angle_corrector_(
correction_data, sensor_configuration_->cloud_min_angle,
sensor_configuration_->cloud_max_angle, sensor_configuration_->cut_angle),
logger_(rclcpp::get_logger("HesaiDecoder"))
scan_cut_angles_(
{deg2rad(sensor_configuration_->cloud_min_angle),
deg2rad(sensor_configuration_->cloud_max_angle), deg2rad(sensor_configuration_->cut_angle)}),
logger_(logger)
{
logger_.set_level(rclcpp::Logger::Level::Debug);

decode_pc_ = std::make_shared<NebulaPointCloud>();
output_pc_ = std::make_shared<NebulaPointCloud>();

if (!sensor_configuration->downsample_mask_path.empty()) {
mask_filter_ = point_filters::DownsampleMaskFilter(
sensor_configuration->downsample_mask_path, SensorT::fov_mdeg.azimuth,
SensorT::peak_resolution_mdeg.azimuth, SensorT::packet_t::n_channels,
logger_->child("Downsample Mask"), true);
}

decode_pc_->reserve(SensorT::max_scan_buffer_points);
output_pc_->reserve(SensorT::max_scan_buffer_points);

scan_cut_angles_ = {
deg2rad(sensor_configuration_->cloud_min_angle),
deg2rad(sensor_configuration_->cloud_max_angle), deg2rad(sensor_configuration_->cut_angle)};
}

int unpack(const std::vector<uint8_t> & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -220,6 +220,8 @@ class Pandar128E3X : public HesaiSensor<hesai_packet::Packet128E3X>
static constexpr float min_range = 0.1;
static constexpr float max_range = 230.0;
static constexpr size_t max_scan_buffer_points = 691200;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-25'000, 14'400}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{100, 125};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,8 @@ class Pandar128E4X : public HesaiSensor<hesai_packet::Packet128E4X>
static constexpr float min_range = 0.1;
static constexpr float max_range = 230.0;
static constexpr size_t max_scan_buffer_points = 691200;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-24'800, 14'400}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{100, 125};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#pragma once

#include "nebula_decoders/nebula_decoders_common/angles.hpp"
#include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp"
#include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp"

Expand Down Expand Up @@ -74,6 +75,8 @@ class Pandar40 : public HesaiSensor<hesai_packet::Packet40P>
static constexpr float min_range = 0.3f;
static constexpr float max_range = 200.f;
static constexpr size_t max_scan_buffer_points = 144000;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-25'000, 15'000}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{200, 334};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ class Pandar64 : public HesaiSensor<hesai_packet::Packet64>
static constexpr float min_range = 0.3f;
static constexpr float max_range = 200.f;
static constexpr size_t max_scan_buffer_points = 230400;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-25'000, 15'000}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{200, 167};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,9 @@ class PandarAT128
static constexpr float min_range = 1.f;
static constexpr float max_range = 180.0f;
static constexpr size_t max_scan_buffer_points = 307200;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{
{30'000, 150'000}, {-12'500, 12'900}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{100, 200};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,8 @@ class PandarQT128 : public HesaiSensor<hesai_packet::PacketQT128C2X>
static constexpr float min_range = 0.05;
static constexpr float max_range = 50.0;
static constexpr size_t max_scan_buffer_points = 172800;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-52'630, 52'630}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{400, 100};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,8 @@ class PandarQT64 : public HesaiSensor<hesai_packet::PacketQT64>
static constexpr float min_range = 0.1f;
static constexpr float max_range = 60.f;
static constexpr size_t max_scan_buffer_points = 76800;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-52'100, 52'100}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{600, 1'450};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ class PandarXT16 : public HesaiSensor<hesai_packet::PacketXT16>
static constexpr float min_range = 0.05f;
static constexpr float max_range = 120.0f;
static constexpr size_t max_scan_buffer_points = 128000;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-15'000, 15'000}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{180, 1'000};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ class PandarXT32 : public HesaiSensor<hesai_packet::PacketXT32>
static constexpr float min_range = 0.05f;
static constexpr float max_range = 120.0f;
static constexpr size_t max_scan_buffer_points = 256000;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-16'000, 15'000}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{180, 1'000};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ class PandarXT32M : public HesaiSensor<hesai_packet::PacketXT32M2X>
static constexpr float min_range = 0.5f;
static constexpr float max_range = 300.0f;
static constexpr size_t max_scan_buffer_points = 384000;
static constexpr FieldOfView<int32_t, MilliDegrees> fov_mdeg{{0, 360'000}, {-20'800, 19'500}};
static constexpr AnglePair<int32_t, MilliDegrees> peak_resolution_mdeg{180, 1'300};

int get_packet_relative_point_time_offset(
uint32_t block_id, uint32_t channel_id, const packet_t & packet) override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include "nebula_common/point_types.hpp"
#include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp"

#include <nebula_common/loggers/logger.hpp>

#include <pcl_conversions/pcl_conversions.h>

#include <memory>
Expand All @@ -34,6 +36,7 @@ class HesaiDriver
private:
/// @brief Current driver status
Status driver_status_;
std::shared_ptr<loggers::Logger> logger_;
/// @brief Decoder according to the model
std::shared_ptr<HesaiScanDecoder> scan_decoder_;

Expand All @@ -52,7 +55,8 @@ class HesaiDriver
explicit HesaiDriver(
const std::shared_ptr<const drivers::HesaiSensorConfiguration> & sensor_configuration,
const std::shared_ptr<const drivers::HesaiCalibrationConfigurationBase> &
calibration_configuration);
calibration_configuration,
const std::shared_ptr<loggers::Logger> & logger);

/// @brief Get current status of this driver
/// @return Current status
Expand Down
19 changes: 6 additions & 13 deletions nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,13 @@
#include <tuple>
#include <vector>

// #define WITH_DEBUG_STD_COUT_HESAI_CLIENT // Use std::cout messages for debugging

namespace nebula::drivers
{
HesaiDriver::HesaiDriver(
const std::shared_ptr<const HesaiSensorConfiguration> & sensor_configuration,
const std::shared_ptr<const HesaiCalibrationConfigurationBase> & calibration_data)
const std::shared_ptr<const HesaiCalibrationConfigurationBase> & calibration_data,
const std::shared_ptr<loggers::Logger> & logger)
: logger_(logger)
{
// initialize proper parser from cloud config's model and echo mode
driver_status_ = nebula::Status::OK;
Expand Down Expand Up @@ -78,17 +78,17 @@ std::shared_ptr<HesaiScanDecoder> HesaiDriver::initialize_decoder(
{
using CalibT = typename SensorT::angle_corrector_t::correction_data_t;
return std::make_shared<HesaiDecoder<SensorT>>(
sensor_configuration, std::dynamic_pointer_cast<const CalibT>(calibration_configuration));
sensor_configuration, std::dynamic_pointer_cast<const CalibT>(calibration_configuration),
logger_->child("Decoder"));
}

std::tuple<drivers::NebulaPointCloudPtr, double> HesaiDriver::parse_cloud_packet(
const std::vector<uint8_t> & packet)
{
std::tuple<drivers::NebulaPointCloudPtr, double> pointcloud;
auto logger = rclcpp::get_logger("HesaiDriver");

if (driver_status_ != nebula::Status::OK) {
RCLCPP_ERROR(logger, "Driver not OK.");
logger_->error("Driver not OK.");
return pointcloud;
}

Expand All @@ -97,13 +97,6 @@ std::tuple<drivers::NebulaPointCloudPtr, double> HesaiDriver::parse_cloud_packet
pointcloud = scan_decoder_->get_pointcloud();
}

// todo
// if (cnt == 0) {
// RCLCPP_ERROR_STREAM(
// logger, "Scanned " << pandar_scan->packets.size() << " packets, but no "
// << "pointclouds were generated. Last azimuth: " << last_azimuth);
// }

return pointcloud;
}

Expand Down
1 change: 1 addition & 0 deletions nebula_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ include_directories(

link_libraries(
${nebula_common_TARGETS}
${nebula_ros_TARGETS}
${rosbag2_cpp_TARGETS}
${PCL_LIBRARIES}
)
Expand Down
18 changes: 9 additions & 9 deletions nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,15 @@

#include "hesai/hesai_ros_offline_extract_bag_pcd.hpp"

#include "rclcpp/serialization.hpp"
#include "rclcpp/serialized_message.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "rosbag2_cpp/reader.hpp"
#include "rosbag2_cpp/readers/sequential_reader.hpp"
#include "rosbag2_cpp/writers/sequential_writer.hpp"
#include "rosbag2_storage/storage_options.hpp"

#include <nebula_common/hesai/hesai_common.hpp>
#include <nebula_ros/common/rclcpp_logger.hpp>
#include <rclcpp/serialization.hpp>
#include <rclcpp/serialized_message.hpp>
#include <rcpputils/filesystem_helper.hpp>
#include <rosbag2_cpp/reader.hpp>
#include <rosbag2_cpp/readers/sequential_reader.hpp>
#include <rosbag2_cpp/writers/sequential_writer.hpp>
#include <rosbag2_storage/storage_options.hpp>

#include <pcl_conversions/pcl_conversions.h>

Expand Down Expand Up @@ -76,7 +76,7 @@ Status HesaiRosOfflineExtractBag::initialize_driver(
{
driver_ptr_ = std::make_shared<drivers::HesaiDriver>(
std::static_pointer_cast<drivers::HesaiSensorConfiguration>(sensor_configuration),
calibration_configuration);
calibration_configuration, std::make_shared<drivers::loggers::RclcppLogger>(get_logger()));
return driver_ptr_->get_status();
}

Expand Down
Loading

0 comments on commit 74ec71a

Please sign in to comment.