Skip to content

Commit dbada66

Browse files
committed
Merge remote-tracking branch 'origin/develop' into pre-commit-fixes
2 parents da0bb68 + 204eb45 commit dbada66

File tree

59 files changed

+8033
-317
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

59 files changed

+8033
-317
lines changed

.cspell.json

+2
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
"Msop",
2929
"nohup",
3030
"nproc",
31+
"nsec",
3132
"ntoa",
3233
"pandar",
3334
"PANDAR",
@@ -46,6 +47,7 @@
4647
"struct",
4748
"structs",
4849
"UDP_SEQ",
50+
"usec",
4951
"vccint",
5052
"Vccint",
5153
"Vdat",

.github/workflows/documentation.yml

+11-11
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,8 @@ on:
88
types: [closed]
99
permissions:
1010
contents: write
11+
id-token: write
12+
pages: write
1113
jobs:
1214
deploy:
1315
runs-on: ubuntu-latest
@@ -24,20 +26,18 @@ jobs:
2426
- uses: actions/setup-python@v5
2527
with:
2628
python-version: 3.x
27-
- run: echo "cache_id=$(date --utc '+%V')" >> $GITHUB_ENV
28-
- uses: actions/cache@v4
29-
with:
30-
key: mkdocs-material-${{ env.cache_id }}
31-
path: .cache
32-
restore-keys: |
33-
mkdocs-material-
3429
- run: |
3530
sudo apt update && sudo apt install -y doxygen && \
36-
pip install mkdocs-material \
37-
mkdocs \
31+
pip install mkdocs \
3832
mkdocs-material \
3933
Jinja2 \
4034
ruamel.yaml && \
4135
pip install git+https://github.com/JakubAndrysek/mkdoxy
42-
- run: pip install mkdocs-material
43-
- run: mkdocs gh-deploy --force
36+
- run: mkdocs build --site-dir _site
37+
- run: touch _site/.nojekyll
38+
- run: |
39+
chmod -c -R +rX "_site/" | while read line; do
40+
echo "::warning title=Invalid file permissions automatically fixed::$line"
41+
done
42+
- uses: actions/upload-pages-artifact@v3
43+
- uses: actions/deploy-pages@v4

build_depends.repos

+1-1
Original file line numberDiff line numberDiff line change
@@ -8,4 +8,4 @@ repositories:
88
ros2_socketcan:
99
type: git
1010
url: https://github.com/knzo25/ros2_socketcan
11-
version: feat/continental_fd
11+
version: feat/continental_fd

nebula_common/include/nebula_common/continental/continental_ars548.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,8 @@
1414

1515
#pragma once
1616

17-
#include <nebula_common/nebula_common.hpp>
18-
#include <nebula_common/nebula_status.hpp>
17+
#include "nebula_common/nebula_common.hpp"
18+
#include "nebula_common/nebula_status.hpp"
1919

2020
#include <boost/algorithm/string/join.hpp>
2121
#include <boost/endian/buffers.hpp>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,296 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#pragma once
16+
17+
#include "nebula_common/nebula_common.hpp"
18+
#include "nebula_common/nebula_status.hpp"
19+
20+
#include <boost/endian/buffers.hpp>
21+
22+
#include <pcl/point_cloud.h>
23+
#include <pcl/point_types.h>
24+
25+
#include <bitset>
26+
#include <cmath>
27+
#include <cstddef>
28+
#include <cstdint>
29+
#include <ctime>
30+
#include <fstream>
31+
#include <iostream>
32+
#include <sstream>
33+
#include <string>
34+
35+
namespace nebula
36+
{
37+
namespace drivers
38+
{
39+
namespace continental_srr520
40+
{
41+
42+
/// @brief struct for SRR520 sensor configuration
43+
struct ContinentalSRR520SensorConfiguration : CANSensorConfigurationBase
44+
{
45+
std::string base_frame{};
46+
bool sync_use_bus_time{};
47+
float configuration_vehicle_wheelbase{};
48+
};
49+
50+
/// @brief Convert ContinentalSRR520SensorConfiguration to string (Overloading the <<
51+
/// operator)
52+
/// @param os
53+
/// @param arg
54+
/// @return stream
55+
inline std::ostream & operator<<(
56+
std::ostream & os, ContinentalSRR520SensorConfiguration const & arg)
57+
{
58+
os << (CANSensorConfigurationBase)(arg) << ", BaseFrame: " << arg.base_frame
59+
<< ", SyncUseBusTime: " << arg.sync_use_bus_time
60+
<< ", ConfigurationVehicleWheelbase: " << arg.configuration_vehicle_wheelbase;
61+
return os;
62+
}
63+
64+
using boost::endian::big_float32_buf_t;
65+
using boost::endian::big_uint16_buf_t;
66+
using boost::endian::big_uint32_buf_t;
67+
using boost::endian::big_uint64_buf_t;
68+
69+
// CAN MSG IDS
70+
constexpr int RDI_NEAR_HEADER_CAN_MESSAGE_ID = 900;
71+
constexpr int RDI_NEAR_ELEMENT_CAN_MESSAGE_ID = 901;
72+
constexpr int RDI_HRR_HEADER_CAN_MESSAGE_ID = 1100;
73+
constexpr int RDI_HRR_ELEMENT_CAN_MESSAGE_ID = 1101;
74+
constexpr int OBJECT_HEADER_CAN_MESSAGE_ID = 1200;
75+
constexpr int OBJECT_CAN_MESSAGE_ID = 1201;
76+
constexpr int CRC_LIST_CAN_MESSAGE_ID = 800;
77+
constexpr int STATUS_CAN_MESSAGE_ID = 700;
78+
constexpr int SYNC_FOLLOW_UP_CAN_MESSAGE_ID = 53;
79+
constexpr int VEH_DYN_CAN_MESSAGE_ID = 600;
80+
constexpr int SENSOR_CONFIG_CAN_MESSAGE_ID = 601;
81+
82+
// CRC IDS
83+
constexpr int NEAR_CRC_ID = 0;
84+
constexpr int HRR_CRC_ID = 1;
85+
constexpr int OBJECT_CRC_ID = 2;
86+
constexpr int TIME_DOMAIN_ID =
87+
0; // For details, please refer to AUTOSAR's "Time Synchronization over CAN" document
88+
89+
constexpr int RDI_NEAR_HEADER_PACKET_SIZE = 32;
90+
constexpr int RDI_NEAR_ELEMENT_PACKET_SIZE = 64;
91+
constexpr int RDI_HRR_HEADER_PACKET_SIZE = 32;
92+
constexpr int RDI_HRR_ELEMENT_PACKET_SIZE = 64;
93+
constexpr int OBJECT_HEADER_PACKET_SIZE = 32;
94+
constexpr int OBJECT_PACKET_SIZE = 64;
95+
constexpr int CRC_LIST_PACKET_SIZE = 4;
96+
constexpr int STATUS_PACKET_SIZE = 64;
97+
constexpr int SYNC_FOLLOW_UP_CAN_PACKET_SIZE = 8;
98+
constexpr int VEH_DYN_CAN_PACKET_SIZE = 8;
99+
constexpr int CONFIGURATION_PACKET_SIZE = 16;
100+
101+
constexpr int RDI_NEAR_PACKET_NUM = 50;
102+
constexpr int RDI_HRR_PACKET_NUM = 20;
103+
constexpr int OBJECT_PACKET_NUM = 20;
104+
105+
constexpr int FRAGMENTS_PER_DETECTION_PACKET = 10;
106+
constexpr int FRAGMENTS_PER_OBJECT_PACKET = 2;
107+
constexpr int DETECTION_FRAGMENT_SIZE = 6;
108+
constexpr int OBJECT_FRAGMENT_SIZE = 31;
109+
110+
constexpr int MAX_RDI_NEAR_DETECTIONS = RDI_NEAR_PACKET_NUM * FRAGMENTS_PER_DETECTION_PACKET;
111+
constexpr int MAX_RDI_HRR_DETECTIONS = RDI_HRR_PACKET_NUM * FRAGMENTS_PER_DETECTION_PACKET;
112+
constexpr int MAX_OBJECTS = OBJECT_PACKET_NUM * FRAGMENTS_PER_OBJECT_PACKET;
113+
114+
#pragma pack(push, 1)
115+
116+
struct StatusPacket
117+
{
118+
big_uint32_buf_t u_time_stamp; // 0
119+
big_uint32_buf_t u_global_time_stamp_sec; // 4
120+
big_uint32_buf_t u_global_time_stamp_nsec; // 8
121+
uint8_t u_global_time_stamp_sync_status; // 12
122+
uint8_t u_sw_version_major; // 13
123+
uint8_t u_sw_version_minor; // 14
124+
uint8_t u_sw_version_patch; // 15
125+
uint8_t u_sensor_id; // 16
126+
big_uint16_buf_t u_long_pos; // 17
127+
big_uint16_buf_t u_lat_pos; // 19
128+
big_uint16_buf_t u_vert_pos; // 21
129+
big_uint16_buf_t u_long_pos_cog; // 23
130+
big_uint16_buf_t u_wheelbase; // 25
131+
big_uint16_buf_t u_yaw_angle; // 27
132+
big_uint16_buf_t u_cover_damping; // 29
133+
uint8_t u_plug_orientation; // 31
134+
uint8_t u_defective; // 32
135+
uint8_t u_supply_voltage_limit; // 33
136+
uint8_t u_sensor_off_temp; // 34
137+
uint8_t u_dynamics_invalid0; // 35
138+
uint8_t u_dynamics_invalid1; // 36
139+
uint8_t u_ext_disturbed; // 37
140+
uint8_t u_com_error; // 38
141+
big_uint16_buf_t u_sw_error; // 39
142+
uint8_t u_aln_status_azimuth_available; // 41
143+
big_uint16_buf_t u_aln_current_azimuth_std; // 42
144+
big_uint16_buf_t u_aln_current_azimuth; // 44
145+
big_uint16_buf_t u_aln_current_delta; // 46
146+
uint8_t reserved1[13]; // Reserved fields, no change needed
147+
big_uint16_buf_t u_crc; // 61
148+
uint8_t u_sequence_counter; // 63
149+
};
150+
151+
struct ScanHeaderPacket
152+
{
153+
big_uint32_buf_t u_time_stamp; // 0
154+
big_uint32_buf_t u_global_time_stamp_sec; // 4
155+
big_uint32_buf_t u_global_time_stamp_nsec; // 8
156+
uint8_t u_global_time_stamp_sync_status; // 12
157+
uint8_t u_signal_status; // 13
158+
uint8_t u_sequence_counter; // 14
159+
big_uint32_buf_t u_cycle_counter; // 15
160+
big_uint16_buf_t u_v_ambiguous; // 19
161+
big_uint16_buf_t u_max_range; // 21
162+
big_uint16_buf_t u_number_of_detections; // 23
163+
uint8_t reserved[7]; // 25
164+
};
165+
166+
struct DetectionFragmentPacket
167+
{
168+
uint8_t data[DETECTION_FRAGMENT_SIZE];
169+
};
170+
171+
struct DetectionPacket
172+
{
173+
DetectionFragmentPacket fragments[FRAGMENTS_PER_DETECTION_PACKET]; // 0 - 59
174+
uint8_t reserved0; // 60
175+
uint8_t reserved1; // 61
176+
uint8_t u_message_counter; // 62
177+
uint8_t u_sequence_counter; // 63
178+
};
179+
180+
struct ObjectHeaderPacket
181+
{
182+
big_uint32_buf_t u_time_stamp; // 0
183+
big_uint32_buf_t u_global_time_stamp_sec; // 4
184+
big_uint32_buf_t u_global_time_stamp_nsec; // 8
185+
uint8_t u_global_time_stamp_sync_status; // 12
186+
uint8_t u_signal_status; // 13
187+
uint8_t u_sequence_counter; // 14
188+
big_uint32_buf_t u_cycle_counter; // 15
189+
big_uint16_buf_t u_ego_vx; // 19
190+
big_uint16_buf_t u_ego_yaw_rate; // 21
191+
uint8_t u_motion_type; // 23
192+
uint8_t u_number_of_objects; // 24
193+
uint8_t reserved[7]; // 25
194+
};
195+
196+
struct ObjectFragmentPacket
197+
{
198+
uint8_t data[OBJECT_FRAGMENT_SIZE];
199+
};
200+
201+
struct ObjectPacket
202+
{
203+
ObjectFragmentPacket fragments[FRAGMENTS_PER_OBJECT_PACKET]; // 0 - 61
204+
uint8_t u_message_counter; // 62
205+
uint8_t u_sequence_counter; // 63
206+
};
207+
208+
struct ConfigurationPacket
209+
{
210+
uint8_t u_sensor_id;
211+
big_uint16_buf_t u_long_pose;
212+
big_uint16_buf_t u_lat_pose;
213+
big_uint16_buf_t u_vert_pos;
214+
big_uint16_buf_t u_long_pos_cog;
215+
big_uint16_buf_t u_wheelbase;
216+
big_uint16_buf_t u_yaw_angle;
217+
big_uint16_buf_t u_cover_damping;
218+
uint8_t u_plug_orientation_and_default_settings;
219+
};
220+
221+
struct SyncPacket
222+
{
223+
uint8_t u_type;
224+
uint8_t u_crc;
225+
uint8_t u_time_domain_and_sequence_counter;
226+
uint8_t u_user_data0;
227+
big_uint32_buf_t u_sync_time_sec;
228+
};
229+
230+
struct FollowUpPacket
231+
{
232+
uint8_t u_type;
233+
uint8_t u_crc;
234+
uint8_t u_time_domain_and_sequence_counter;
235+
uint8_t u_reserved;
236+
big_uint32_buf_t u_sync_time_nsec;
237+
};
238+
239+
#pragma pack(pop)
240+
241+
struct EIGEN_ALIGN16 PointSRR520Detection
242+
{
243+
PCL_ADD_POINT4D;
244+
float range;
245+
float azimuth;
246+
float range_rate;
247+
float rcs;
248+
uint8_t pdh00;
249+
uint8_t pdh01;
250+
uint8_t pdh02;
251+
uint8_t pdh03;
252+
uint8_t pdh04;
253+
uint8_t pdh05;
254+
float snr;
255+
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
256+
};
257+
258+
// Note we only use a subset of the data since POINT_CLOUD_REGISTER_POINT_STRUCT has a limit in the
259+
// number of fields
260+
struct EIGEN_ALIGN16 PointSRR520Object
261+
{
262+
PCL_ADD_POINT4D;
263+
uint32_t id;
264+
uint16_t age;
265+
float orientation;
266+
float rcs;
267+
float score;
268+
uint8_t object_status;
269+
float dynamics_abs_vel_x;
270+
float dynamics_abs_vel_y;
271+
float dynamics_abs_acc_x;
272+
float dynamics_abs_acc_y;
273+
float box_length;
274+
float box_width;
275+
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
276+
};
277+
278+
} // namespace continental_srr520
279+
} // namespace drivers
280+
} // namespace nebula
281+
282+
POINT_CLOUD_REGISTER_POINT_STRUCT(
283+
nebula::drivers::continental_srr520::PointSRR520Detection,
284+
(float, x, x)(float, y, y)(float, z, z)(float, azimuth, azimuth)(float, range, range)(
285+
float, range_rate, range_rate)(int8_t, rcs, rcs)(uint8_t, pdh00, pdh00)(uint8_t, pdh01, pdh01)(
286+
uint8_t, pdh02,
287+
pdh02)(uint16_t, pdh03, pdh03)(uint8_t, pdh04, pdh04)(uint8_t, pdh05, pdh05)(float, snr, snr))
288+
289+
POINT_CLOUD_REGISTER_POINT_STRUCT(
290+
nebula::drivers::continental_srr520::PointSRR520Object,
291+
(float, x, x)(float, y, y)(float, z, z)(uint32_t, id, id)(uint16_t, age, age)(
292+
float, orientation,
293+
orientation)(float, rcs, rcs)(float, score, score)(uint8_t, object_status, object_status)(
294+
float, dynamics_abs_vel_x, dynamics_abs_vel_x)(float, dynamics_abs_vel_y, dynamics_abs_vel_y)(
295+
float, dynamics_abs_acc_x, dynamics_abs_acc_x)(float, dynamics_abs_acc_y, dynamics_abs_acc_y)(
296+
float, box_length, box_length)(float, box_width, box_width))

0 commit comments

Comments
 (0)