15#ifndef CARMA_COOPERATIVE_PERCEPTION__MSG_CONVERSION_HPP_
16#define CARMA_COOPERATIVE_PERCEPTION__MSG_CONVERSION_HPP_
20#include <carma_cooperative_perception_interfaces/msg/detection_list.hpp>
21#include <carma_cooperative_perception_interfaces/msg/track.hpp>
22#include <carma_cooperative_perception_interfaces/msg/track_list.hpp>
23#include <carma_perception_msgs/msg/external_object.hpp>
24#include <carma_perception_msgs/msg/external_object_list.hpp>
25#include <carma_v2x_msgs/msg/sensor_data_sharing_message.hpp>
31#include <geometry_msgs/msg/pose_stamped.hpp>
33#include <lanelet2_core/geometry/Lanelet.h>
34#include <lanelet2_extension/projection/local_frame_projector.h>
36#include <tf2/LinearMath/Quaternion.h>
44auto to_time_msg(
const DDateTime & d_date_time) -> builtin_interfaces::msg::Time;
50 -> j2735_v2x_msgs::msg::DDateTime;
53 const builtin_interfaces::msg::Time & external_object_list_time,
54 const builtin_interfaces::msg::Time & external_object_time)
55 -> carma_v2x_msgs::msg::MeasurementTimeOffset;
57auto to_position_msg(
const UtmCoordinate & position_utm) -> geometry_msgs::msg::Point;
59auto heading_to_enu_yaw(
const units::angle::degree_t & heading) -> units::angle::degree_t;
62 const geometry_msgs::msg::PoseStamped & current_pose,
63 const carma_v2x_msgs::msg::PositionOffsetXYZ & detected_object_data)
64 -> carma_v2x_msgs::msg::PositionOffsetXYZ;
67 const geometry_msgs::msg::PoseStamped & source_pose,
68 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
69 -> carma_v2x_msgs::msg::Position3D;
72 const carma_v2x_msgs::msg::SensorDataSharingMessage & sdsm, std::string_view georeference)
73 -> carma_cooperative_perception_interfaces::msg::DetectionList;
78 carma_cooperative_perception_interfaces::msg::Detection::MOTION_MODEL_CTRV};
80 carma_cooperative_perception_interfaces::msg::Detection::MOTION_MODEL_CTRV};
82 carma_cooperative_perception_interfaces::msg::Detection::MOTION_MODEL_CTRV};
84 carma_cooperative_perception_interfaces::msg::Detection::MOTION_MODEL_CTRV};
86 carma_cooperative_perception_interfaces::msg::Detection::MOTION_MODEL_CTRV};
90 const carma_perception_msgs::msg::ExternalObject &
object,
91 const MotionModelMapping & motion_model_mapping)
95 const carma_perception_msgs::msg::ExternalObjectList & object_list,
96 const MotionModelMapping & motion_model_mapping)
97 -> carma_cooperative_perception_interfaces::msg::DetectionList;
100 -> carma_perception_msgs::msg::ExternalObject;
103 const carma_cooperative_perception_interfaces::msg::TrackList & track_list)
104 -> carma_perception_msgs::msg::ExternalObjectList;
107 const carma_perception_msgs::msg::ExternalObjectList & external_object_list,
108 const geometry_msgs::msg::PoseStamped & current_pose,
109 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
110 -> carma_v2x_msgs::msg::SensorDataSharingMessage;
114 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
115 -> carma_v2x_msgs::msg::DetectedObjectData;
118 double yaw,
const lanelet::BasicPoint3d & obj_pose,
119 const std::shared_ptr<lanelet::projection::LocalFrameProjector> & map_projection)
120 -> units::angle::degree_t;
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 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 to_detection_msg(const carma_perception_msgs::msg::ExternalObject &object, const MotionModelMapping &motion_model_mapping) -> carma_cooperative_perception_interfaces::msg::Detection
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 ¤t_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 ¤t_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::SensorDataSharingMessage
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
std::uint8_t large_vehicle_model
std::uint8_t unknown_model
std::uint8_t pedestrian_model
std::uint8_t motorcycle_model
std::uint8_t small_vehicle_model