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

feat(nebula_ros): add json schema #153

Merged
Merged
Show file tree
Hide file tree
Changes from 77 commits
Commits
Show all changes
135 commits
Select commit Hold shift + click to select a range
0d252f3
fix(hesai_hw_interface): add error handling
mojomex Mar 28, 2024
3468d96
Merge branch 'main' into hesai-hw-interface-error-handling
amc-nu Apr 2, 2024
aff2733
fix(hesai_decoder): print config instead of config address
mojomex Mar 21, 2024
e9e05a6
refactor(nebula_ros): combine Hesai wrapper nodes into one
mojomex Mar 21, 2024
f997555
refactor: remove pandarScan pub/sub, decode one packet at a time
mojomex Mar 21, 2024
39d050c
reword later
mojomex Mar 26, 2024
d839329
temporary progress
mojomex Mar 26, 2024
fdbeb45
fix(hesai_ros_wrapper): remove changes wrongly merged during rebase
mojomex Apr 4, 2024
cc26aeb
fix(hesai_ros_wrapper): increase packet buffering to stop internal pa…
mojomex Apr 4, 2024
a1b9f5b
feat(nebula_common): add instrumentation tools
mojomex Apr 4, 2024
1131201
feat(hesai_ros_wrapper): instrument code on critical path
mojomex Apr 4, 2024
174bd1c
disable instrumentation
mojomex Apr 5, 2024
195eb10
feat(hesai): move received buffer into ros message instead of copy
mojomex Apr 5, 2024
295d501
feat(hesai_ros_wrapper: add thread-safe queue between udp receiver an…
mojomex Apr 5, 2024
bdec15d
feat(nebula_common): more instrumentation tools
mojomex Apr 5, 2024
017cfad
fix: update link to transport_drivers fork
mojomex Apr 5, 2024
e69e313
Merge branch 'main' into hesai-hw-interface-error-handling
mojomex Apr 8, 2024
6713b0d
fix(hesai_hw_monitor_ros_wrapper): fixed wrong range given for S/N copy
mojomex Apr 8, 2024
cd6ad8e
update GitHub PR view
mojomex Apr 8, 2024
decf1ac
fix(hesai): print uint8, uint16 as numbers
mojomex Apr 8, 2024
da8fd64
refactor(mt_queue): make variables more readable
mojomex Apr 8, 2024
dc850fb
perf(hesai_ros_wrapper): update queue capacity to alleviate packet dr…
mojomex Apr 8, 2024
d5d98a2
chore(hesai_ros_wrapper): remove unused pub/sub
mojomex Apr 8, 2024
1403984
refactor(hesai_ros_wrapper): clean up control flow, member variables
mojomex Apr 8, 2024
5c8204c
Merge branch 'hesai-hw-interface-error-handling' into single-node-ref…
mojomex Apr 8, 2024
b203176
feat(hesai_ros_wrapper): publish/subscribe to legacy pandar_packets o…
mojomex Apr 9, 2024
bebae29
change launch file back to single-threaded container
mojomex Apr 9, 2024
38072d4
attempt to make queue contention less bad
mojomex Apr 10, 2024
0215d7c
chore(hesai_ros_wrapper): reduce logging output
mojomex Apr 11, 2024
d0f10cb
feat(hesai_ros_wrapper): print warning when connected to HW and recei…
mojomex Apr 11, 2024
7fd450b
feat(nebula_launch.py): throw error when trying to launch Hesai senso…
mojomex Apr 12, 2024
a857d50
chore: update cspell ignore
mojomex Apr 16, 2024
77b933f
refactor(nebula_ros): split single wrapper file into 3 sub-wrappers
mojomex Apr 18, 2024
19e8101
chore(velodyne_calibration_decoder): fix spelling
mojomex Apr 18, 2024
c2b78ea
Merge branch 'hesai-hw-interface-error-handling' into single-node-ref…
mojomex Apr 18, 2024
f0a8599
chore(nebula_common): remove debug code
mojomex Apr 18, 2024
4f022cd
chore(velodyne_calibration_decoder): fix spelling
mojomex Apr 18, 2024
440adb5
Merge branch 'hesai-hw-interface-error-handling' into single-node-ref…
mojomex Apr 18, 2024
bd08a1a
fix(hesai_decoder): initialize last_phase to prevent empty pointclou…
mojomex Apr 18, 2024
68227d1
fix(nebula_tests): make Hesai tests compile again
mojomex Apr 18, 2024
e3c297a
fix(nebula_examples): make Hesai examples compile again
mojomex Apr 18, 2024
d9e6fa3
chore(velodyne_calibration_decoder): fix spelling once and for all
mojomex Apr 18, 2024
187ad04
chore(velodyne_calibration_decoder): fix spelling once and for all
mojomex Apr 18, 2024
7663459
Merge branch 'main' into single-node-refactor
mojomex Apr 18, 2024
1bfba05
fix(nebula_examples): fix test failure (remove ament_lint_common)
mojomex Apr 18, 2024
02bb644
Merge branch 'main' into hesai-hw-interface-error-handling
mojomex Apr 18, 2024
4d3bf5b
fix(hesai_hw_interface): add missing check for PTC error, make error …
mojomex Apr 22, 2024
f39d58f
Merge branch 'hesai-hw-interface-error-handling' into single-node-ref…
mojomex Apr 22, 2024
5bba66d
refactor(hesai): re-introduce parameter update mechanism
mojomex Apr 23, 2024
37bc575
feat(hesai_ros): add watchdog timer for pointcloud output
mojomex Apr 23, 2024
f190d67
Merge branch 'main' into single-node-refactor
mojomex Apr 25, 2024
eb80e3a
fix(hesai): change to possibly more accurate high_resolution_clock
mojomex Apr 25, 2024
0f0456a
fix(hesai): fix crash on QT128
mojomex Apr 25, 2024
897bfb4
refactor(hesai_hw_interface): refactor repeated error handling code
mojomex Apr 30, 2024
8a11d98
fix(hesai_launch_all_hw.xml): set valid RPM when AT128 is selected
mojomex Apr 30, 2024
657fac7
refactor(hesai_decoder): remove redundant arguments for correction/ca…
mojomex Apr 30, 2024
74388c9
refactor(nebula_ros): move mt_queue to common
mojomex May 11, 2024
8aeca9b
refactor(velodyne)!: unify wrapper nodes. Currently WIP but compiling
mojomex May 16, 2024
8d1f470
fix(velodyne_decoders): after the last commit, point clouds weren't …
mojomex May 17, 2024
b2343d5
fix(velodyne_tests): make tests compile with the new decoder API
mojomex May 17, 2024
c004ac1
fix(velodyne_examples): make examples compile with new decoder API
mojomex May 17, 2024
d34ef8d
feat(velodyne_hw_interface): synchronous, null- and thread-safe HTTP …
mojomex May 17, 2024
5a91d32
fix(velodyne_launch_all_hw.xml): refactor to single-node
mojomex May 17, 2024
62d7f92
fix(velodyne): make hw interface wrapper work with new hw interface API
mojomex May 17, 2024
f18215d
fix(velodyne): implement correct locking behavior in hw monitor wrapper
mojomex May 17, 2024
290f5d1
Merge remote-tracking branch 'origin/main' into single-node-refactor-…
mojomex May 17, 2024
0ae9198
fix(nebula_tests): re-cut scans in existing reference data correctly …
mojomex May 20, 2024
cf68687
chore(velodyne_scan_decoder.hpp): explicitly initialize some fields f…
mojomex May 20, 2024
d003540
Merge remote-tracking branch 'origin/main' into single-node-refactor-…
mojomex May 20, 2024
2f31805
feat(nebula_ros): add velodyne json schema
amadeuszsz May 17, 2024
0de4ffb
chore(nebula_ros): update config
May 20, 2024
a39a167
chore(nebula_ros): update schema
May 20, 2024
236600d
chore(nebula): add json schema workflow
May 20, 2024
30d963d
ci(nebula): use of autoware actions repo
amadeuszsz May 21, 2024
0512283
chore(nebula_ros): add schema composition
amadeuszsz May 21, 2024
dff369f
chore(pre-commit): autoupdate hooks
mojomex May 22, 2024
e7a8049
fix(hesai_decoder): print config instead of config address
mojomex Mar 21, 2024
737e752
refactor(nebula_ros): combine Hesai wrapper nodes into one
mojomex Mar 21, 2024
6baee80
refactor: remove pandarScan pub/sub, decode one packet at a time
mojomex Mar 21, 2024
cbd15d3
reword later
mojomex Mar 26, 2024
892a48b
temporary progress
mojomex Mar 26, 2024
2148676
fix(hesai_ros_wrapper): remove changes wrongly merged during rebase
mojomex Apr 4, 2024
4923a46
fix(hesai_ros_wrapper): increase packet buffering to stop internal pa…
mojomex Apr 4, 2024
ff9096b
feat(nebula_common): add instrumentation tools
mojomex Apr 4, 2024
fc16852
feat(hesai_ros_wrapper): instrument code on critical path
mojomex Apr 4, 2024
b7a5a89
disable instrumentation
mojomex Apr 5, 2024
d04af0e
feat(hesai): move received buffer into ros message instead of copy
mojomex Apr 5, 2024
bc8813a
feat(hesai_ros_wrapper: add thread-safe queue between udp receiver an…
mojomex Apr 5, 2024
232afae
feat(nebula_common): more instrumentation tools
mojomex Apr 5, 2024
e9afe52
fix: update link to transport_drivers fork
mojomex Apr 5, 2024
1f1e92e
update GitHub PR view
mojomex Apr 8, 2024
617373a
refactor(mt_queue): make variables more readable
mojomex Apr 8, 2024
b81f2a9
perf(hesai_ros_wrapper): update queue capacity to alleviate packet dr…
mojomex Apr 8, 2024
18cb875
chore(hesai_ros_wrapper): remove unused pub/sub
mojomex Apr 8, 2024
0cdcd80
refactor(hesai_ros_wrapper): clean up control flow, member variables
mojomex Apr 8, 2024
162e754
fix(hesai_hw_interface): add error handling
mojomex Mar 28, 2024
9bdadd2
fix(hesai_hw_monitor_ros_wrapper): fixed wrong range given for S/N copy
mojomex Apr 8, 2024
49e03d4
fix(hesai): print uint8, uint16 as numbers
mojomex Apr 8, 2024
bc718ef
feat(hesai_ros_wrapper): publish/subscribe to legacy pandar_packets o…
mojomex Apr 9, 2024
4ff8878
change launch file back to single-threaded container
mojomex Apr 9, 2024
8fb516e
attempt to make queue contention less bad
mojomex Apr 10, 2024
a0631bd
chore(hesai_ros_wrapper): reduce logging output
mojomex Apr 11, 2024
43fad46
feat(hesai_ros_wrapper): print warning when connected to HW and recei…
mojomex Apr 11, 2024
243fc75
feat(nebula_launch.py): throw error when trying to launch Hesai senso…
mojomex Apr 12, 2024
2c14f48
refactor(nebula_ros): split single wrapper file into 3 sub-wrappers
mojomex Apr 18, 2024
10388c9
chore: update cspell ignore
mojomex Apr 16, 2024
7d78b84
chore(velodyne_calibration_decoder): fix spelling
mojomex Apr 18, 2024
a063a5f
chore(nebula_common): remove debug code
mojomex Apr 18, 2024
9ff53af
chore(velodyne_calibration_decoder): fix spelling
mojomex Apr 18, 2024
f3f8f3c
fix(hesai_decoder): initialize last_phase to prevent empty pointclou…
mojomex Apr 18, 2024
e3b42f0
fix(nebula_tests): make Hesai tests compile again
mojomex Apr 18, 2024
cb6fe32
fix(nebula_examples): make Hesai examples compile again
mojomex Apr 18, 2024
d45c0eb
chore(velodyne_calibration_decoder): fix spelling once and for all
mojomex Apr 18, 2024
012908e
fix(nebula_examples): fix test failure (remove ament_lint_common)
mojomex Apr 18, 2024
34ff9e8
fix(hesai_hw_interface): add missing check for PTC error, make error …
mojomex Apr 22, 2024
3f42a2a
refactor(hesai): re-introduce parameter update mechanism
mojomex Apr 23, 2024
9d89ff1
feat(hesai_ros): add watchdog timer for pointcloud output
mojomex Apr 23, 2024
df702eb
fix(hesai): change to possibly more accurate high_resolution_clock
mojomex Apr 25, 2024
54ce7ea
fix(hesai): fix crash on QT128
mojomex Apr 25, 2024
ddab198
refactor(hesai_hw_interface): refactor repeated error handling code
mojomex Apr 30, 2024
09f074a
fix(hesai_launch_all_hw.xml): set valid RPM when AT128 is selected
mojomex Apr 30, 2024
be1a7e7
refactor(hesai_decoder): remove redundant arguments for correction/ca…
mojomex Apr 30, 2024
00fefb4
refactor(nebula_ros): move mt_queue to common
mojomex May 11, 2024
4b8b9c0
chore(nebula_examples): change output rosbag format to NebulaPackets,…
mojomex May 22, 2024
52a210c
chore(hesai/decoder_wrapper): clarify watchdog behavior in decoder
mojomex May 22, 2024
c4d58ec
chore(hesai/hw_monitor_wrapper): fix typo in diagnostics name
mojomex May 22, 2024
884a85c
chore(hesai_ros_decoder_test): fix unclear naming in console output
mojomex May 22, 2024
798c9ec
chore(nebula_ros): add schema composition for robosense
amadeuszsz May 22, 2024
28b42fc
chore: run pre-commit and implement suggested fixes (not including co…
mojomex May 22, 2024
5edde8b
Merge branch 'parameter-schema' into single-node-refactor-velodyne-sc…
amadeuszsz May 22, 2024
13a538e
fix(expected.hpp): revert explicit constructors
mojomex May 22, 2024
8f01847
chore: remove erroneously added node_modules folder
mojomex May 22, 2024
1f00fa6
chore(gitconfig): exclude node_modules from git
mojomex May 22, 2024
0fdd8b6
Merge branch 'single-node-refactor' into single-node-refactor-velodyn…
amadeuszsz May 22, 2024
0dc2cb5
fix(nebula_tests): missing serialization format
amadeuszsz May 22, 2024
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
16 changes: 15 additions & 1 deletion .cspell.json
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,26 @@
"adctp",
"Adctp",
"AT",
"autosar",
"block_id",
"Bpearl",
"calib",
"DHAVE",
"Difop",
"extrinsics",
"gprmc",
"gptp",
"Helios",
"Hesai",
"Idat",
"ipaddr",
"manc",
"memcpy",
"mkdoxy",
"Msop",
"nohup",
"nproc",
"ntoa",
"pandar",
"PANDAR",
"PANDARAT",
Expand All @@ -23,13 +35,15 @@
"QT",
"rclcpp",
"schedutil",
"srvs",
"STD_COUT",
"stds",
"struct",
"structs",
"UDP_SEQ",
"vccint",
"Vccint",
"Vdat",
"XT",
"XTM",
"DHAVE",
Expand All @@ -49,4 +63,4 @@
"Piyush",
"fout"
]
}
}
40 changes: 40 additions & 0 deletions .github/workflows/json-schema-check.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
name: json-schema-check

on:
pull_request:
workflow_dispatch:

jobs:
check-if-relevant-files-changed:
runs-on: ubuntu-latest
outputs:
run-check: ${{ steps.paths_filter.outputs.json_or_yaml }}
steps:
- uses: actions/checkout@v4
- uses: dorny/paths-filter@v3
id: paths_filter
with:
filters: |
json_or_yaml:
- '**/schema/*.schema.json'
- '**/schema/sub/.json'
- '**/config/**/*.param.yaml'

json-schema-check:
needs: check-if-relevant-files-changed
if: needs.check-if-relevant-files-changed.outputs.run-check == 'true'
runs-on: ubuntu-latest
steps:
- name: Check out repository
uses: actions/checkout@v4

- name: Run json-schema-check
uses: autowarefoundation/autoware-github-actions/json-schema-check@v1

no-relevant-changes:
needs: check-if-relevant-files-changed
if: needs.check-if-relevant-files-changed.outputs.run-check == 'false'
runs-on: ubuntu-latest
steps:
- name: Dummy step
run: echo "No relevant changes, passing check"
4 changes: 2 additions & 2 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,5 @@ repositories:
# TCP version of transport drivers
transport_drivers:
type: git
url: https://github.com/MapIV/transport_drivers
version: boost
url: https://github.com/mojomex/transport_drivers
version: mutable-buffer-in-udp-callback
2 changes: 2 additions & 0 deletions nebula_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ ament_auto_add_library(nebula_common SHARED
src/velodyne/velodyne_calibration_decoder.cpp
)

target_link_libraries(nebula_common yaml-cpp)

ament_auto_package()

# Set ROS_DISTRO macros
Expand Down
35 changes: 26 additions & 9 deletions nebula_common/include/nebula_common/hesai/hesai_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace nebula
namespace drivers
{
/// @brief struct for Hesai sensor configuration
struct HesaiSensorConfiguration : LidarConfigurationBase
struct HesaiSensorConfiguration : public LidarConfigurationBase
{
uint16_t gnss_port{};
double scan_phase{};
Expand Down Expand Up @@ -43,13 +43,20 @@ inline std::ostream & operator<<(std::ostream & os, HesaiSensorConfiguration con
return os;
}

struct HesaiCalibrationConfigurationBase : public CalibrationConfigurationBase
{
virtual nebula::Status LoadFromBytes(const std::vector<uint8_t> & buf) = 0;
virtual nebula::Status LoadFromFile(const std::string & calibration_file) = 0;
virtual nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector<uint8_t> & buf) = 0;
};

/// @brief struct for Hesai calibration configuration
struct HesaiCalibrationConfiguration : CalibrationConfigurationBase
struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase
{
std::map<size_t, float> elev_angle_map;
std::map<size_t, float> azimuth_offset_map;

inline nebula::Status LoadFromFile(const std::string & calibration_file)
inline nebula::Status LoadFromFile(const std::string & calibration_file) override
{
std::ifstream ifs(calibration_file);
if (!ifs) {
Expand All @@ -61,6 +68,11 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase
return LoadFromString(ss.str());
}

nebula::Status LoadFromBytes(const std::vector<uint8_t> & buf) {
std::string calibration_string = std::string(buf.begin(), buf.end());
return LoadFromString(calibration_string);
}

/// @brief Loading calibration data
/// @param calibration_content
/// @return Resulting status
Expand Down Expand Up @@ -99,7 +111,7 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase
/// @brief Saving calibration data (not used)
/// @param calibration_file
/// @return Resulting status
inline nebula::Status SaveFile(const std::string & calibration_file)
inline nebula::Status SaveToFile(const std::string & calibration_file)
{
std::ofstream ofs(calibration_file);
if (!ofs) {
Expand All @@ -117,6 +129,11 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase
return Status::OK;
}

nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector<uint8_t> & buf) override {
std::string calibration_string = std::string(buf.begin(), buf.end());
return SaveFileFromString(calibration_file, calibration_string);
}

/// @brief Saving calibration data from string
/// @param calibration_file path
/// @param calibration_string calibration string
Expand All @@ -134,7 +151,7 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase
};

/// @brief struct for Hesai correction configuration (for AT)
struct HesaiCorrection
struct HesaiCorrection : public HesaiCalibrationConfigurationBase
{
uint16_t delimiter;
uint8_t versionMajor;
Expand All @@ -156,7 +173,7 @@ struct HesaiCorrection
/// @brief Load correction data from file
/// @param buf Binary buffer
/// @return Resulting status
inline nebula::Status LoadFromBinary(const std::vector<uint8_t> & buf)
inline nebula::Status LoadFromBytes(const std::vector<uint8_t> & buf) override
{
size_t index;
for (index = 0; index < buf.size()-1; index++) {
Expand Down Expand Up @@ -258,7 +275,7 @@ struct HesaiCorrection
/// @brief Load correction data from file
/// @param correction_file path
/// @return Resulting status
inline nebula::Status LoadFromFile(const std::string & correction_file)
inline nebula::Status LoadFromFile(const std::string & correction_file) override
{
std::ifstream ifs(correction_file, std::ios::in | std::ios::binary);
if (!ifs) {
Expand All @@ -271,7 +288,7 @@ struct HesaiCorrection
ifs.read((char *)&c, sizeof(unsigned char));
buf.emplace_back(c);
}
LoadFromBinary(buf);
LoadFromBytes(buf);

ifs.close();
return Status::OK;
Expand All @@ -281,7 +298,7 @@ struct HesaiCorrection
/// @param correction_file path
/// @param buf correction binary
/// @return Resulting status
inline nebula::Status SaveFileFromBinary(const std::string & correction_file, const std::vector<uint8_t> & buf)
inline nebula::Status SaveToFileFromBytes(const std::string & correction_file, const std::vector<uint8_t> & buf) override
{
std::cerr << "Saving in:" << correction_file << "\n";
std::ofstream ofs(correction_file, std::ios::trunc | std::ios::binary);
Expand Down
6 changes: 3 additions & 3 deletions nebula_common/include/nebula_common/nebula_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +346,7 @@ enum class PtpProfile {
IEEE_1588v2 = 0,
IEEE_802_1AS,
IEEE_802_1AS_AUTO,
PROFILE_UNKNOWN
UNKNOWN_PROFILE
};

enum class PtpTransportType {
Expand Down Expand Up @@ -624,7 +624,7 @@ inline PtpProfile PtpProfileFromString(const std::string & ptp_profile)
if (tmp_str == "802.1as") return PtpProfile::IEEE_802_1AS;
if (tmp_str == "automotive") return PtpProfile::IEEE_802_1AS_AUTO;

return PtpProfile::PROFILE_UNKNOWN;
return PtpProfile::UNKNOWN_PROFILE;
}

/// @brief Convert PtpProfile enum to string (Overloading the << operator)
Expand All @@ -643,7 +643,7 @@ inline std::ostream & operator<<(std::ostream & os, nebula::drivers::PtpProfile
case PtpProfile::IEEE_802_1AS_AUTO:
os << "IEEE_802.1AS Automotive";
break;
case PtpProfile::PROFILE_UNKNOWN:
case PtpProfile::UNKNOWN_PROFILE:
os << "UNKNOWN";
break;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,19 +23,11 @@ struct CorrectedAngleData

/// @brief Handles angle correction for given azimuth/channel combinations, as well as trigonometry
/// lookup tables
template <typename CorrectionDataT>
class AngleCorrector
{
protected:
const std::shared_ptr<HesaiCalibrationConfiguration> sensor_calibration_;
const std::shared_ptr<HesaiCorrection> sensor_correction_;

public:
AngleCorrector(
const std::shared_ptr<HesaiCalibrationConfiguration> & sensor_calibration,
const std::shared_ptr<HesaiCorrection> & sensor_correction)
: sensor_calibration_(sensor_calibration), sensor_correction_(sensor_correction)
{
}
using correction_data_t = CorrectionDataT;

/// @brief Get the corrected azimuth and elevation for a given block and channel, along with their
/// sin/cos values.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ namespace drivers
{

template <size_t ChannelN, size_t AngleUnit>
class AngleCorrectorCalibrationBased : public AngleCorrector
class AngleCorrectorCalibrationBased : public AngleCorrector<HesaiCalibrationConfiguration>
{
private:
static constexpr size_t MAX_AZIMUTH_LEN = 360 * AngleUnit;
Expand All @@ -27,18 +27,16 @@ class AngleCorrectorCalibrationBased : public AngleCorrector

public:
AngleCorrectorCalibrationBased(
const std::shared_ptr<HesaiCalibrationConfiguration> & sensor_calibration,
const std::shared_ptr<HesaiCorrection> & sensor_correction)
: AngleCorrector(sensor_calibration, sensor_correction)
const std::shared_ptr<const HesaiCalibrationConfiguration> & sensor_calibration)
{
if (sensor_calibration == nullptr) {
throw std::runtime_error(
"Cannot instantiate AngleCorrectorCalibrationBased without calibration data");
}

for (size_t channel_id = 0; channel_id < ChannelN; ++channel_id) {
float elevation_angle_deg = sensor_calibration->elev_angle_map[channel_id];
float azimuth_offset_deg = sensor_calibration->azimuth_offset_map[channel_id];
float elevation_angle_deg = sensor_calibration->elev_angle_map.at(channel_id);
float azimuth_offset_deg = sensor_calibration->azimuth_offset_map.at(channel_id);

elevation_angle_rad_[channel_id] = deg2rad(elevation_angle_deg);
azimuth_offset_rad_[channel_id] = deg2rad(azimuth_offset_deg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,11 @@ namespace drivers
{

template <size_t ChannelN, size_t AngleUnit>
class AngleCorrectorCorrectionBased : public AngleCorrector
class AngleCorrectorCorrectionBased : public AngleCorrector<HesaiCorrection>
{
private:
static constexpr size_t MAX_AZIMUTH_LENGTH = 360 * AngleUnit;
const std::shared_ptr<const HesaiCorrection> correction_;
rclcpp::Logger logger_;

std::array<float, MAX_AZIMUTH_LENGTH> cos_{};
Expand All @@ -31,26 +32,25 @@ class AngleCorrectorCorrectionBased : public AngleCorrector
// * none of the startFrames are defined as > 360 deg (< 0 not possible since they are unsigned)
// * the fields are arranged in ascending order (e.g. field 1: 20-140deg, field 2: 140-260deg etc.)
// These assumptions hold for AT128E2X.
int field = sensor_correction_->frameNumber - 1;
for (size_t i = 0; i < sensor_correction_->frameNumber; ++i) {
if (azimuth < sensor_correction_->startFrame[i]) return field;
int field = correction_->frameNumber - 1;
for (size_t i = 0; i < correction_->frameNumber; ++i) {
if (azimuth < correction_->startFrame[i]) return field;
field = i;
}

// This is never reached if sensor_correction_ is correct
// This is never reached if correction_ is correct
return field;
}

public:
AngleCorrectorCorrectionBased(
const std::shared_ptr<HesaiCalibrationConfiguration> & sensor_calibration,
const std::shared_ptr<HesaiCorrection> & sensor_correction)
: AngleCorrector(sensor_calibration, sensor_correction),
const std::shared_ptr<const HesaiCorrection> & sensor_correction)
: correction_(sensor_correction),
logger_(rclcpp::get_logger("AngleCorrectorCorrectionBased"))
{
if (sensor_correction == nullptr) {
throw std::runtime_error(
"Cannot instantiate AngleCorrectorCalibrationBased without calibration data");
"Cannot instantiate AngleCorrectorCorrectionBased without correction data");
}

logger_.set_level(rclcpp::Logger::Level::Debug);
Expand All @@ -64,17 +64,16 @@ class AngleCorrectorCorrectionBased : public AngleCorrector

CorrectedAngleData getCorrectedAngleData(uint32_t block_azimuth, uint32_t channel_id) override
{
const auto & correction = AngleCorrector::sensor_correction_;
int field = findField(block_azimuth);

auto elevation =
correction->elevation[channel_id] +
correction->getElevationAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100);
correction_->elevation[channel_id] +
correction_->getElevationAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100);
elevation = (MAX_AZIMUTH_LENGTH + elevation) % MAX_AZIMUTH_LENGTH;

auto azimuth = (block_azimuth + MAX_AZIMUTH_LENGTH - correction->startFrame[field]) * 2 -
correction->azimuth[channel_id] +
correction->getAzimuthAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100);
auto azimuth = (block_azimuth + MAX_AZIMUTH_LENGTH - correction_->startFrame[field]) * 2 -
correction_->azimuth[channel_id] +
correction_->getAzimuthAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100);
azimuth = (MAX_AZIMUTH_LENGTH + azimuth) % MAX_AZIMUTH_LENGTH;

float azimuth_rad = 2.f * azimuth * M_PI / MAX_AZIMUTH_LENGTH;
Expand Down
Loading
Loading