Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
msg_conversion.cpp
Go to the documentation of this file.
1// Copyright 2023 Leidos
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
16
17#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
18#include <carma_cooperative_perception_interfaces/msg/track.hpp>
19#include <carma_cooperative_perception_interfaces/msg/track_list.hpp>
20#include <carma_perception_msgs/msg/external_object.hpp>
21#include <carma_perception_msgs/msg/external_object_list.hpp>
22#include <j2735_v2x_msgs/msg/d_date_time.hpp>
23#include <j2735_v2x_msgs/msg/personal_device_user_type.hpp>
24#include <j2735_v2x_msgs/to_floating_point.hpp>
25#include <j3224_v2x_msgs/msg/detected_object_data.hpp>
26#include <j3224_v2x_msgs/msg/measurement_time_offset.hpp>
27#include <j3224_v2x_msgs/msg/object_type.hpp>
28#include <j2735_v2x_msgs/msg/positional_accuracy.hpp>
29#include <j3224_v2x_msgs/msg/equipment_type.hpp>
30
31#include <algorithm>
32#include <cctype>
33#include <charconv>
34#include <chrono>
35#include <cmath>
36#include <limits>
37#include <numeric>
38#include <string>
39#include <utility>
40
41#include <proj.h>
42#include <gsl/pointers>
43#include <memory>
44
49
50#include <lanelet2_core/geometry/Lanelet.h>
51#include <lanelet2_extension/projection/local_frame_projector.h>
52#include <boost/date_time/posix_time/conversion.hpp>
53#include <boost/date_time/posix_time/posix_time_io.hpp>
54#include "boost/date_time/posix_time/posix_time.hpp"
55
57{
58auto to_time_msg(const DDateTime & d_date_time) -> builtin_interfaces::msg::Time
59{
60 double seconds;
61 const auto fractional_secs{std::modf(
62 remove_units(units::time::second_t{d_date_time.hour.value_or(units::time::second_t{0.0})}) +
63 remove_units(units::time::second_t{d_date_time.minute.value_or(units::time::second_t{0.0})}) +
64 remove_units(units::time::second_t{d_date_time.second.value_or(units::time::second_t{0.0})}),
65 &seconds)};
66
67 builtin_interfaces::msg::Time msg;
68 msg.sec = static_cast<std::int32_t>(seconds);
69 msg.nanosec = static_cast<std::int32_t>(fractional_secs * 1e9);
70
71 return msg;
72}
73
75 -> DDateTime
76{
77 sdsm_time.second.value() += offset.measurement_time_offset;
78
79 return sdsm_time;
80}
81
82auto ned_to_enu(const PositionOffsetXYZ & offset_ned) noexcept
83{
84 auto offset_enu{offset_ned};
85
86 // NED to ENU: swap x and y axis and negate z axis
87 offset_enu.offset_x = offset_ned.offset_y;
88 offset_enu.offset_y = offset_ned.offset_x;
89
90 if (offset_enu.offset_z) {
91 offset_enu.offset_z.value() *= -1;
92 }
93
94 return offset_enu;
95}
96
97auto to_ddate_time_msg(const builtin_interfaces::msg::Time & builtin_time)
98 -> j2735_v2x_msgs::msg::DDateTime
99{
100 j2735_v2x_msgs::msg::DDateTime ddate_time_output;
101
102 // Add the time components from epoch seconds
103 boost::posix_time::ptime posix_time = boost::posix_time::from_time_t(builtin_time.sec) +
104 boost::posix_time::nanosec(builtin_time.nanosec);
105
106 const auto time_stamp_year = posix_time.date().year();
107 const auto time_stamp_month = posix_time.date().month();
108 const auto time_stamp_day = posix_time.date().day();
109
110 const auto hours_of_day = posix_time.time_of_day().hours();
111 const auto minutes_of_hour = posix_time.time_of_day().minutes();
112 const auto seconds_of_minute = posix_time.time_of_day().seconds();
113
114 ddate_time_output.presence_vector = 0;
115
116 ddate_time_output.presence_vector |= j2735_v2x_msgs::msg::DDateTime::YEAR;
117 ddate_time_output.year.year = time_stamp_year;
118 ddate_time_output.presence_vector |= j2735_v2x_msgs::msg::DDateTime::MONTH;
119 ddate_time_output.month.month = time_stamp_month;
120 ddate_time_output.presence_vector |= j2735_v2x_msgs::msg::DDateTime::DAY;
121 ddate_time_output.day.day = time_stamp_day;
122 ddate_time_output.presence_vector |= j2735_v2x_msgs::msg::DDateTime::HOUR;
123 ddate_time_output.hour.hour = hours_of_day;
124 ddate_time_output.presence_vector |= j2735_v2x_msgs::msg::DDateTime::MINUTE;
125 ddate_time_output.minute.minute = minutes_of_hour;
126 ddate_time_output.presence_vector |= j2735_v2x_msgs::msg::DDateTime::SECOND;
127 ddate_time_output.second.millisecond = seconds_of_minute;
128
129 return ddate_time_output;
130}
131
133 const builtin_interfaces::msg::Time & external_object_list_stamp,
134 const builtin_interfaces::msg::Time & external_object_stamp)
135 -> carma_v2x_msgs::msg::MeasurementTimeOffset
136{
137 carma_v2x_msgs::msg::MeasurementTimeOffset time_offset;
138
139 boost::posix_time::ptime external_object_list_time =
140 boost::posix_time::from_time_t(external_object_list_stamp.sec) +
141 boost::posix_time::nanosec(external_object_list_stamp.nanosec);
142
143 boost::posix_time::ptime external_object_time =
144 boost::posix_time::from_time_t(external_object_stamp.sec) +
145 boost::posix_time::nanosec(external_object_stamp.nanosec);
146
147 boost::posix_time::time_duration offset_duration =
148 (external_object_list_time - external_object_time);
149
150 time_offset.measurement_time_offset = offset_duration.total_seconds();
151
152 return time_offset;
153}
154
155auto to_position_msg(const UtmCoordinate & position_utm) -> geometry_msgs::msg::Point
156{
157 geometry_msgs::msg::Point msg;
158
159 msg.x = remove_units(position_utm.easting);
160 msg.y = remove_units(position_utm.northing);
161 msg.z = remove_units(position_utm.elevation);
162
163 return msg;
164}
165
166auto to_position_msg(const MapCoordinate & position_map) -> geometry_msgs::msg::Point
167{
168 geometry_msgs::msg::Point msg;
169
170 msg.x = remove_units(position_map.easting);
171 msg.y = remove_units(position_map.northing);
172 msg.z = remove_units(position_map.elevation);
173
174 return msg;
175}
176
177auto heading_to_enu_yaw(const units::angle::degree_t & heading) -> units::angle::degree_t
178{
179 return units::angle::degree_t{std::fmod(-(remove_units(heading) - 90.0) + 360.0, 360.0)};
180}
181
183 double yaw, const lanelet::BasicPoint3d & obj_pose,
184 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
185 -> units::angle::degree_t
186{
187 // Get object geodetic position
188 lanelet::GPSPoint wgs_obj_pose = map_projection->reverse(obj_pose);
189
190 // Get WGS84 Heading
191 gsl::owner<PJ_CONTEXT *> context = proj_context_create();
192 gsl::owner<PJ *> transform = proj_create(context, map_projection->ECEF_PROJ_STR);
193 units::angle::degree_t grid_heading{std::fmod(90 - yaw + 360, 360)};
194
195 const auto factors = proj_factors(
196 transform, proj_coord(proj_torad(wgs_obj_pose.lon), proj_torad(wgs_obj_pose.lat), 0, 0));
197 units::angle::degree_t grid_convergence{proj_todeg(factors.meridian_convergence)};
198
199 auto wgs_heading = grid_convergence + grid_heading;
200
201 proj_destroy(transform);
202 proj_context_destroy(context);
203
204 return wgs_heading;
205}
206
207// determine the object position offset in m from the current reference pose
208// in map frame and external object pose
210 const geometry_msgs::msg::PoseStamped & source_pose,
211 const carma_v2x_msgs::msg::PositionOffsetXYZ & position_offset)
212 -> carma_v2x_msgs::msg::PositionOffsetXYZ
213{
214 carma_v2x_msgs::msg::PositionOffsetXYZ adjusted_offset;
215
216 adjusted_offset.offset_x.object_distance =
217 position_offset.offset_x.object_distance - source_pose.pose.position.x;
218 adjusted_offset.offset_y.object_distance =
219 position_offset.offset_y.object_distance - source_pose.pose.position.y;
220 adjusted_offset.offset_z.object_distance =
221 position_offset.offset_z.object_distance - source_pose.pose.position.z;
222 adjusted_offset.presence_vector = carma_v2x_msgs::msg::PositionOffsetXYZ::HAS_OFFSET_Z;
223
224 return adjusted_offset;
225}
226
228 const geometry_msgs::msg::PoseStamped & source_pose,
229 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
230 -> carma_v2x_msgs::msg::Position3D
231{
232 carma_v2x_msgs::msg::Position3D ref_pos;
233 lanelet::BasicPoint3d source_pose_basicpoint{
234 source_pose.pose.position.x, source_pose.pose.position.y, 0.0};
235
236 lanelet::GPSPoint wgs84_ref_pose = map_projection->reverse(source_pose_basicpoint);
237
238 ref_pos.longitude = wgs84_ref_pose.lon;
239 ref_pos.latitude = wgs84_ref_pose.lat;
240 ref_pos.elevation = wgs84_ref_pose.ele;
241 ref_pos.elevation_exists = true;
242
243 return ref_pos;
244}
245
247 const carma_v2x_msgs::msg::SensorDataSharingMessage & sdsm, std::string_view georeference)
248 -> carma_cooperative_perception_interfaces::msg::DetectionList
249{
250 carma_cooperative_perception_interfaces::msg::DetectionList detection_list;
251
252 const auto ref_pos_3d{Position3D::from_msg(sdsm.ref_pos)};
253 const Wgs84Coordinate ref_pos_wgs84{
254 ref_pos_3d.latitude, ref_pos_3d.longitude, ref_pos_3d.elevation.value()};
255 const auto ref_pos_map{project_to_carma_map(ref_pos_wgs84, georeference)};
256
257 for (const auto & object_data : sdsm.objects.detected_object_data) {
258 const auto common_data{object_data.detected_object_common_data};
259
261 detection.header.frame_id = "map";
262
263 const auto detection_time{calc_detection_time_stamp(
264 DDateTime::from_msg(sdsm.sdsm_time_stamp),
265 MeasurementTimeOffset::from_msg(common_data.measurement_time))};
266
267 detection.header.stamp = to_time_msg(detection_time);
268
269 // TemporaryID and octet string terms come from the SAE J2735 message definitions
270 static constexpr auto to_string = [](const std::vector<std::uint8_t> & temporary_id) {
271 std::string str;
272 str.reserve(2 * std::size(temporary_id)); // Two hex characters per octet string
273
274 std::array<char, 2> buffer;
275 for (const auto & octet_string : temporary_id) {
276 std::to_chars(std::begin(buffer), std::end(buffer), octet_string, 16);
277 str.push_back(std::toupper(std::get<0>(buffer)));
278 str.push_back(std::toupper(std::get<1>(buffer)));
279 }
280
281 return str;
282 };
283
284 detection.id =
285 to_string(sdsm.source_id.id) + "-" + std::to_string(common_data.detected_id.object_id);
286
287 const auto pos_offset_enu{ned_to_enu(PositionOffsetXYZ::from_msg(common_data.pos))};
288 detection.pose.pose.position = to_position_msg(MapCoordinate{
289 ref_pos_map.easting + pos_offset_enu.offset_x, ref_pos_map.northing + pos_offset_enu.offset_y,
290 ref_pos_map.elevation + pos_offset_enu.offset_z.value_or(units::length::meter_t{0.0})});
291
292 // Pose covariance is flattened 6x6 matrix with rows/columns of x, y, z, roll, pitch, yaw
293 try {
294 detection.pose.covariance.at(0) =
295 0.5 * std::pow(j2735_v2x_msgs::to_double(common_data.pos_confidence.pos).value(), 2);
296 detection.pose.covariance.at(7) =
297 0.5 * std::pow(j2735_v2x_msgs::to_double(common_data.pos_confidence.pos).value(), 2);
298 } catch (const std::bad_optional_access &) {
299 throw std::runtime_error("missing position confidence");
300 }
301
302 try {
303 detection.pose.covariance.at(14) =
304 0.5 * std::pow(j2735_v2x_msgs::to_double(common_data.pos_confidence.elevation).value(), 2);
305 } catch (const std::bad_optional_access &) {
306 throw std::runtime_error("missing elevation confidence");
307 }
308
309 const auto true_heading{units::angle::degree_t{Heading::from_msg(common_data.heading).heading}};
310
311 // Note: This should really use the detection's WGS-84 position, so the
312 // convergence will be off slightly. TODO
313 const units::angle::degree_t grid_convergence{
314 calculate_grid_convergence(ref_pos_wgs84, georeference)};
315
316 const auto grid_heading{true_heading - grid_convergence};
317 const auto enu_yaw{heading_to_enu_yaw(grid_heading)};
318
319 tf2::Quaternion quat_tf;
320 quat_tf.setRPY(0, 0, remove_units(units::angle::radian_t{enu_yaw}));
321 detection.pose.pose.orientation = tf2::toMsg(quat_tf);
322
323 try {
324 // Pose covariance is flattened 6x6 matrix with rows/columns of x, y, z, roll, pitch, yaw
325 detection.pose.covariance.at(35) =
326 0.5 * std::pow(j2735_v2x_msgs::to_double(common_data.heading_conf).value(), 2);
327 } catch (const std::bad_optional_access &) {
328 throw std::runtime_error("missing heading confidence");
329 }
330
331 const auto speed{Speed::from_msg(common_data.speed)};
332 detection.twist.twist.linear.x =
333 remove_units(units::velocity::meters_per_second_t{speed.speed});
334
335 const auto speed_z{Speed::from_msg(common_data.speed_z)};
336 detection.twist.twist.linear.z =
337 remove_units(units::velocity::meters_per_second_t{speed_z.speed});
338
339 try {
340 // Twist covariance is flattened 6x6 matrix with rows/columns of x, y, z, roll, pitch, yaw
341 detection.twist.covariance.at(0) =
342 0.5 * std::pow(j2735_v2x_msgs::to_double(common_data.speed_confidence).value(), 2);
343 } catch (const std::bad_optional_access &) {
344 throw std::runtime_error("missing speed confidence");
345 }
346
347 try {
348 detection.twist.covariance.at(14) =
349 0.5 * std::pow(j2735_v2x_msgs::to_double(common_data.speed_confidence_z).value(), 2);
350 } catch (const std::bad_optional_access &) {
351 throw std::runtime_error("missing z-speed confidence");
352 }
353
354 const auto accel_set{AccelerationSet4Way::from_msg(common_data.accel_4_way)};
355 detection.twist.twist.angular.z =
356 remove_units(units::angular_velocity::degrees_per_second_t{accel_set.yaw_rate});
357
358 try {
359 detection.twist.covariance.at(35) =
360 0.5 * std::pow(j2735_v2x_msgs::to_double(common_data.acc_cfd_yaw).value(), 2);
361 } catch (const std::bad_optional_access &) {
362 throw std::runtime_error("missing yaw-rate confidence");
363 }
364
365 switch (common_data.obj_type.object_type) {
366 case common_data.obj_type.ANIMAL:
367 detection.motion_model = detection.MOTION_MODEL_CTRV;
368 // We don't have a good semantic class mapping for animals
369 detection.semantic_class = detection.SEMANTIC_CLASS_UNKNOWN;
370 break;
371 case common_data.obj_type.VRU:
372 detection.motion_model = detection.MOTION_MODEL_CTRV;
373 detection.semantic_class = detection.SEMANTIC_CLASS_PEDESTRIAN;
374 break;
375 case common_data.obj_type.VEHICLE:
376 detection.motion_model = detection.MOTION_MODEL_CTRV;
377 detection.semantic_class = detection.SEMANTIC_CLASS_SMALL_VEHICLE;
378 break;
379 default:
380 detection.motion_model = detection.MOTION_MODEL_CTRV;
381 detection.semantic_class = detection.SEMANTIC_CLASS_UNKNOWN;
382 }
383
384 detection_list.detections.push_back(std::move(detection));
385 }
386
387 return detection_list;
388}
389
391 const carma_perception_msgs::msg::ExternalObject & object,
392 const MotionModelMapping & motion_model_mapping)
394{
396
397 detection.header = object.header;
398
399 if (object.presence_vector & object.BSM_ID_PRESENCE_VECTOR) {
400 detection.id = "";
401 std::transform(
402 std::cbegin(object.bsm_id), std::cend(object.bsm_id), std::back_inserter(detection.id),
403 [](const auto & i) { return i + '0'; });
404 }
405
406 if (object.presence_vector & object.ID_PRESENCE_VECTOR) {
407 detection.id += '-' + std::to_string(object.id);
408 }
409
410 if (object.presence_vector & object.POSE_PRESENCE_VECTOR) {
411 detection.pose = object.pose;
412 }
413
414 if (object.presence_vector & object.VELOCITY_PRESENCE_VECTOR) {
415 detection.twist = object.velocity;
416 }
417
418 if (object.presence_vector & object.OBJECT_TYPE_PRESENCE_VECTOR) {
419 switch (object.object_type) {
420 case object.SMALL_VEHICLE:
421 detection.motion_model = motion_model_mapping.small_vehicle_model;
422 detection.semantic_class = detection.SEMANTIC_CLASS_SMALL_VEHICLE;
423 break;
424 case object.LARGE_VEHICLE:
425 detection.motion_model = motion_model_mapping.large_vehicle_model;
426 detection.semantic_class = detection.SEMANTIC_CLASS_LARGE_VEHICLE;
427 break;
428 case object.MOTORCYCLE:
429 detection.motion_model = motion_model_mapping.motorcycle_model;
430 detection.semantic_class = detection.SEMANTIC_CLASS_MOTORCYCLE;
431 break;
432 case object.PEDESTRIAN:
433 detection.motion_model = motion_model_mapping.pedestrian_model;
434 detection.semantic_class = detection.SEMANTIC_CLASS_PEDESTRIAN;
435 break;
436 case object.UNKNOWN:
437 default:
438 detection.motion_model = motion_model_mapping.unknown_model;
439 detection.semantic_class = detection.SEMANTIC_CLASS_UNKNOWN;
440 }
441 }
442
443 return detection;
444}
445
447 const carma_perception_msgs::msg::ExternalObjectList & object_list,
448 const MotionModelMapping & motion_model_mapping)
449 -> carma_cooperative_perception_interfaces::msg::DetectionList
450{
451 carma_cooperative_perception_interfaces::msg::DetectionList detection_list;
452
453 std::transform(
454 std::cbegin(object_list.objects), std::cend(object_list.objects),
455 std::back_inserter(detection_list.detections),
456 [&motion_model_mapping = std::as_const(motion_model_mapping)](const auto & object) {
457 return to_detection_msg(object, motion_model_mapping);
458 });
459
460 return detection_list;
461}
462
464 -> carma_perception_msgs::msg::ExternalObject
465{
466 carma_perception_msgs::msg::ExternalObject external_object;
467 external_object.header = track.header;
468 external_object.presence_vector = 0;
469
470 const auto to_numeric_id = [](std::string string_id) -> std::optional<uint32_t> {
471 auto non_digit_start = std::remove_if(
472 std::begin(string_id), std::end(string_id),
473 [](const auto & ch) { return !std::isdigit(ch); });
474
475 std::uint32_t numeric_id;
476 const auto digit_substr_size{std::distance(std::begin(string_id), non_digit_start)};
477 if (
478 std::from_chars(string_id.c_str(), string_id.c_str() + digit_substr_size, numeric_id).ec ==
479 std::errc{}) {
480 return numeric_id;
481 }
482
483 return std::nullopt;
484 };
485
486 if (const auto numeric_id{to_numeric_id(track.id)}) {
487 external_object.presence_vector |= external_object.ID_PRESENCE_VECTOR;
488 external_object.id = numeric_id.value();
489 } else {
490 external_object.presence_vector &= ~external_object.ID_PRESENCE_VECTOR;
491 }
492
493 external_object.presence_vector |= external_object.POSE_PRESENCE_VECTOR;
494 external_object.pose = track.pose;
495
496 external_object.presence_vector |= external_object.VELOCITY_PRESENCE_VECTOR;
497
498 const auto track_longitudinal_velocity{track.twist.twist.linear.x};
499 const auto track_orientation = track.pose.pose.orientation;
500
501 tf2::Quaternion q(
502 track_orientation.x, track_orientation.y, track_orientation.z, track_orientation.w);
503 tf2::Matrix3x3 m(q);
504 double roll, pitch, yaw;
505 m.getRPY(roll, pitch, yaw);
506
507 external_object.velocity.twist.linear.x = track_longitudinal_velocity * std::cos(yaw);
508 external_object.velocity.twist.linear.y = track_longitudinal_velocity * std::sin(yaw);
509
510 external_object.object_type = track.semantic_class;
511
512 external_object.presence_vector |= external_object.OBJECT_TYPE_PRESENCE_VECTOR;
513 switch (track.semantic_class) {
514 case track.SEMANTIC_CLASS_SMALL_VEHICLE:
515 external_object.object_type = external_object.SMALL_VEHICLE;
516 break;
517 case track.SEMANTIC_CLASS_LARGE_VEHICLE:
518 external_object.object_type = external_object.LARGE_VEHICLE;
519 break;
520 case track.SEMANTIC_CLASS_MOTORCYCLE:
521 external_object.object_type = external_object.MOTORCYCLE;
522 break;
523 case track.SEMANTIC_CLASS_PEDESTRIAN:
524 external_object.object_type = external_object.PEDESTRIAN;
525 break;
526 case track.SEMANTIC_CLASS_UNKNOWN:
527 default:
528 external_object.object_type = external_object.UNKNOWN;
529 }
530
531 return external_object;
532}
533
535 const carma_cooperative_perception_interfaces::msg::TrackList & track_list)
536 -> carma_perception_msgs::msg::ExternalObjectList
537{
538 carma_perception_msgs::msg::ExternalObjectList external_object_list;
539
540 for (const auto & track : track_list.tracks) {
541 external_object_list.objects.push_back(to_external_object_msg(track));
542 }
543
544 return external_object_list;
545}
546
548 const carma_perception_msgs::msg::ExternalObjectList & external_object_list,
549 const geometry_msgs::msg::PoseStamped & current_pose,
550 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
551 -> carma_v2x_msgs::msg::SensorDataSharingMessage
552{
553 carma_v2x_msgs::msg::SensorDataSharingMessage sdsm;
554 carma_v2x_msgs::msg::DetectedObjectList detected_object_list;
555
556 sdsm.sdsm_time_stamp = to_ddate_time_msg(external_object_list.header.stamp);
557
558 sdsm.ref_pos = transform_pose_from_map_to_wgs84(current_pose, map_projection);
559
560 // Convert external objects within the list to detected_object_data
561 for (const auto & external_object : external_object_list.objects) {
562 auto sdsm_detected_object = to_detected_object_data_msg(external_object, map_projection);
563
564 // Calculate the time offset between individual objects and the respective SDSM container msg
565 sdsm_detected_object.detected_object_common_data.measurement_time =
566 calc_sdsm_time_offset(external_object.header.stamp, external_object.header.stamp);
567
568 // Calculate the position offset from the current reference pose (in m)
569 sdsm_detected_object.detected_object_common_data.pos =
570 calc_relative_position(current_pose, sdsm_detected_object.detected_object_common_data.pos);
571
572 detected_object_list.detected_object_data.push_back(sdsm_detected_object);
573 }
574
575 std::vector<uint8_t> id = {0x00, 0x00, 0x00, 0x01};
576 sdsm.source_id.id = id;
577 sdsm.equipment_type.equipment_type = j3224_v2x_msgs::msg::EquipmentType::OBU;
578 sdsm.ref_pos_xy_conf.semi_major = j2735_v2x_msgs::msg::PositionalAccuracy::ACCURACY_UNAVAILABLE;
579 sdsm.ref_pos_xy_conf.semi_minor = j2735_v2x_msgs::msg::PositionalAccuracy::ACCURACY_UNAVAILABLE;
580 sdsm.ref_pos_xy_conf.orientation = j2735_v2x_msgs::msg::PositionalAccuracy::ACCURACY_ORIENTATION_UNAVAILABLE;
581 sdsm.objects = detected_object_list;
582
583 return sdsm;
584}
585
587 const carma_perception_msgs::msg::ExternalObject & external_object,
588 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
589 -> carma_v2x_msgs::msg::DetectedObjectData
590{
591 carma_v2x_msgs::msg::DetectedObjectData detected_object_data;
592 detected_object_data.presence_vector = 0;
593
594 carma_v2x_msgs::msg::DetectedObjectCommonData detected_object_common_data;
595 detected_object_common_data.presence_vector = 0;
596
597 // common data //////////
598
599 // obj_type_conf - convert from percentile, cast to proper uint type
600 if (external_object.presence_vector & external_object.OBJECT_TYPE_PRESENCE_VECTOR) {
601 detected_object_common_data.obj_type_cfd.classification_confidence =
602 static_cast<std::uint8_t>(external_object.confidence * 100);
603 }
604
605 // detected_id - cast proper type
606 if (external_object.presence_vector & external_object.ID_PRESENCE_VECTOR) {
607 detected_object_common_data.detected_id.object_id =
608 static_cast<std::uint16_t>(external_object.id);
609 }
610
611 // pos - Add offset to ref_pos to get object position
612 // in map frame -> convert to WGS84 coordinates for sdsm
613
614 // To get offset: Subtract the external object pose from
615 // the current vehicle location given by the current_pose topic
616 if (external_object.presence_vector & external_object.POSE_PRESENCE_VECTOR) {
617 detected_object_common_data.pos.offset_x.object_distance =
618 static_cast<float>(external_object.pose.pose.position.x);
619 detected_object_common_data.pos.offset_y.object_distance =
620 static_cast<float>(external_object.pose.pose.position.y);
621 detected_object_common_data.pos.offset_z.object_distance =
622 static_cast<float>(external_object.pose.pose.position.z);
623 }
624
625 // speed/speed_z - convert vector velocity to scalar speed val given x/y components
626 if (external_object.presence_vector & external_object.VELOCITY_PRESENCE_VECTOR) {
627 detected_object_common_data.speed.speed =
628 std::hypot(external_object.velocity.twist.linear.x, external_object.velocity.twist.linear.y);
629
630 detected_object_common_data.presence_vector |=
631 carma_v2x_msgs::msg::DetectedObjectCommonData::HAS_SPEED_Z;
632 detected_object_common_data.speed_z.speed = external_object.velocity.twist.linear.z;
633
634 // heading - convert ang vel to scale heading
635 lanelet::BasicPoint3d external_object_position{
636 external_object.pose.pose.position.x, external_object.pose.pose.position.y,
637 external_object.pose.pose.position.z};
638 // Get yaw from orientation
639 auto obj_orientation = external_object.pose.pose.orientation;
640 tf2::Quaternion q(obj_orientation.x, obj_orientation.y, obj_orientation.z, obj_orientation.w);
641 tf2::Matrix3x3 m(q);
642 double roll, pitch, yaw;
643 m.getRPY(roll, pitch, yaw);
644
645 detected_object_common_data.heading.heading =
646 remove_units(enu_orientation_to_true_heading(yaw, external_object_position, map_projection));
647 }
648
649 // optional data (determine based on object type)
650 // use object type struct for better control
651 carma_v2x_msgs::msg::DetectedObjectOptionalData detected_object_optional_data;
652
653 switch (external_object.object_type) {
654 case external_object.SMALL_VEHICLE:
655 detected_object_common_data.obj_type.object_type = j3224_v2x_msgs::msg::ObjectType::VEHICLE;
656
657 if (external_object.presence_vector & external_object.SIZE_PRESENCE_VECTOR) {
658 detected_object_optional_data.det_veh.presence_vector =
659 carma_v2x_msgs::msg::DetectedVehicleData::HAS_SIZE;
660 detected_object_optional_data.det_veh.presence_vector |=
661 carma_v2x_msgs::msg::DetectedVehicleData::HAS_HEIGHT;
662
663 detected_object_optional_data.det_veh.size.vehicle_width = external_object.size.y;
664 detected_object_optional_data.det_veh.size.vehicle_length = external_object.size.x;
665 detected_object_optional_data.det_veh.height.vehicle_height = external_object.size.z;
666 }
667 break;
668 case external_object.LARGE_VEHICLE:
669 detected_object_common_data.obj_type.object_type = j3224_v2x_msgs::msg::ObjectType::VEHICLE;
670
671 if (external_object.presence_vector & external_object.SIZE_PRESENCE_VECTOR) {
672 detected_object_optional_data.det_veh.presence_vector =
673 carma_v2x_msgs::msg::DetectedVehicleData::HAS_SIZE;
674 detected_object_optional_data.det_veh.presence_vector |=
675 carma_v2x_msgs::msg::DetectedVehicleData::HAS_HEIGHT;
676
677 detected_object_optional_data.det_veh.size.vehicle_width = external_object.size.y;
678 detected_object_optional_data.det_veh.size.vehicle_length = external_object.size.x;
679 detected_object_optional_data.det_veh.height.vehicle_height = external_object.size.z;
680 }
681 break;
682 case external_object.MOTORCYCLE:
683 detected_object_common_data.obj_type.object_type = j3224_v2x_msgs::msg::ObjectType::VEHICLE;
684
685 if (external_object.presence_vector & external_object.SIZE_PRESENCE_VECTOR) {
686 detected_object_optional_data.det_veh.presence_vector =
687 carma_v2x_msgs::msg::DetectedVehicleData::HAS_SIZE;
688 detected_object_optional_data.det_veh.presence_vector |=
689 carma_v2x_msgs::msg::DetectedVehicleData::HAS_HEIGHT;
690
691 detected_object_optional_data.det_veh.size.vehicle_width = external_object.size.y;
692 detected_object_optional_data.det_veh.size.vehicle_length = external_object.size.x;
693 detected_object_optional_data.det_veh.height.vehicle_height = external_object.size.z;
694 }
695 break;
696 case external_object.PEDESTRIAN:
697 detected_object_common_data.obj_type.object_type = j3224_v2x_msgs::msg::ObjectType::VRU;
698
699 detected_object_optional_data.det_vru.presence_vector =
700 carma_v2x_msgs::msg::DetectedVRUData::HAS_BASIC_TYPE;
701 detected_object_optional_data.det_vru.basic_type.type |=
702 j2735_v2x_msgs::msg::PersonalDeviceUserType::A_PEDESTRIAN;
703
704 break;
705 case external_object.UNKNOWN:
706 default:
707 detected_object_common_data.obj_type.object_type = j3224_v2x_msgs::msg::ObjectType::UNKNOWN;
708
709 if (external_object.presence_vector & external_object.SIZE_PRESENCE_VECTOR) {
710 detected_object_optional_data.det_obst.obst_size.width.size_value = external_object.size.y;
711 detected_object_optional_data.det_obst.obst_size.length.size_value = external_object.size.x;
712
713 detected_object_optional_data.det_obst.obst_size.presence_vector =
714 carma_v2x_msgs::msg::ObstacleSize::HAS_HEIGHT;
715 detected_object_optional_data.det_obst.obst_size.height.size_value = external_object.size.z;
716 }
717 }
718
719 detected_object_data.detected_object_common_data = std::move(detected_object_common_data);
720 detected_object_data.detected_object_optional_data = std::move(detected_object_optional_data);
721
722 return detected_object_data;
723}
724
725} // namespace carma_cooperative_perception
auto enu_orientation_to_true_heading(double yaw, const lanelet::BasicPoint3d &obj_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> units::angle::degree_t
auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage &sdsm, std::string_view georeference) -> carma_cooperative_perception_interfaces::msg::DetectionList
auto to_external_object_list_msg(const carma_cooperative_perception_interfaces::msg::TrackList &track_list) -> carma_perception_msgs::msg::ExternalObjectList
auto calc_sdsm_time_offset(const builtin_interfaces::msg::Time &external_object_list_time, const builtin_interfaces::msg::Time &external_object_time) -> carma_v2x_msgs::msg::MeasurementTimeOffset
auto calculate_grid_convergence(const Wgs84Coordinate &position, const UtmZone &zone) -> units::angle::degree_t
Calculate grid convergence at a given position.
Definition: geodetic.cpp:154
auto to_ddate_time_msg(const builtin_interfaces::msg::Time &builtin_time) -> j2735_v2x_msgs::msg::DDateTime
auto calc_detection_time_stamp(DDateTime d_date_time, const MeasurementTimeOffset &offset) -> DDateTime
std::variant< multiple_object_tracking::CtrvDetection, multiple_object_tracking::CtraDetection > Detection
auto project_to_carma_map(const Wgs84Coordinate &coordinate, std::string_view proj_string) -> MapCoordinate
Definition: geodetic.cpp:55
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
auto to_detection_msg(const carma_perception_msgs::msg::ExternalObject &object, const MotionModelMapping &motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::Detection
auto ned_to_enu(const PositionOffsetXYZ &offset_ned) noexcept
auto to_detected_object_data_msg(const carma_perception_msgs::msg::ExternalObject &external_object, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::DetectedObjectData
auto to_time_msg(const DDateTime &d_date_time) -> builtin_interfaces::msg::Time
auto to_external_object_msg(const carma_cooperative_perception_interfaces::msg::Track &track) -> carma_perception_msgs::msg::ExternalObject
auto heading_to_enu_yaw(const units::angle::degree_t &heading) -> units::angle::degree_t
auto calc_relative_position(const geometry_msgs::msg::PoseStamped &current_pose, const carma_v2x_msgs::msg::PositionOffsetXYZ &detected_object_data) -> carma_v2x_msgs::msg::PositionOffsetXYZ
auto to_sdsm_msg(const carma_perception_msgs::msg::ExternalObjectList &external_object_list, const geometry_msgs::msg::PoseStamped &current_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::SensorDataSharingMessage
constexpr auto remove_units(const T &value)
auto to_position_msg(const UtmCoordinate &position_utm) -> geometry_msgs::msg::Point
std::variant< multiple_object_tracking::CtrvTrack, multiple_object_tracking::CtraTrack > Track
auto transform_pose_from_map_to_wgs84(const geometry_msgs::msg::PoseStamped &source_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::Position3D
static auto from_msg(const j2735_v2x_msgs::msg::AccelerationSet4Way &msg) -> AccelerationSet4Way
Definition: j2735_types.cpp:55
static auto from_msg(const j2735_v2x_msgs::msg::DDateTime &msg) -> DDateTime
Definition: j2735_types.cpp:19
std::optional< units::time::second_t > second
Definition: j2735_types.hpp:43
static auto from_msg(const j2735_v2x_msgs::msg::Heading &heading) -> Heading
static auto from_msg(const j3224_v2x_msgs::msg::MeasurementTimeOffset &msg) -> MeasurementTimeOffset
Definition: j3224_types.cpp:47
static auto from_msg(const j2735_v2x_msgs::msg::Position3D &msg) -> Position3D
Definition: j2735_types.cpp:75
static auto from_msg(const j3224_v2x_msgs::msg::PositionOffsetXYZ &msg) -> PositionOffsetXYZ
Definition: j3224_types.cpp:19
static auto from_msg(const j2735_v2x_msgs::msg::Speed &speed) -> Speed
Represents a position using UTM coordinates.
Definition: geodetic.hpp:50
Represents a position using WGS-84 coordinates.
Definition: geodetic.hpp:33