15#ifndef MOTION_COMPUTATION__MESSAGE_CONVERSIONS_HPP_
16#define MOTION_COMPUTATION__MESSAGE_CONVERSIONS_HPP_
18#include <lanelet2_extension/projection/local_frame_projector.h>
19#include <tf2/LinearMath/Quaternion.h>
23#include <rclcpp/rclcpp.hpp>
25#include <carma_perception_msgs/msg/external_object.hpp>
26#include <carma_v2x_msgs/msg/bsm.hpp>
27#include <carma_v2x_msgs/msg/mobility_path.hpp>
28#include <carma_v2x_msgs/msg/psm.hpp>
35 const carma_v2x_msgs::msg::PSM & in_msg, carma_perception_msgs::msg::ExternalObject & out_msg,
36 const std::string & map_frame_id,
double pred_period,
double pred_step_size,
37 const lanelet::projection::LocalFrameProjector & map_projector,
38 const tf2::Quaternion & ned_in_map_rotation,
39 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock);
42 const carma_v2x_msgs::msg::BSM & in_msg, carma_perception_msgs::msg::ExternalObject & out_msg,
43 const std::string & map_frame_id,
double pred_period,
double pred_step_size,
44 const lanelet::projection::LocalFrameProjector & map_projector,
45 tf2::Quaternion ned_in_map_rotation);
48 const carma_v2x_msgs::msg::MobilityPath & in_msg,
49 carma_perception_msgs::msg::ExternalObject & out_msg,
50 const lanelet::projection::LocalFrameProjector & map_projector);
void convert(const carma_v2x_msgs::msg::PSM &in_msg, carma_perception_msgs::msg::ExternalObject &out_msg, const std::string &map_frame_id, double pred_period, double pred_step_size, const lanelet::projection::LocalFrameProjector &map_projector, const tf2::Quaternion &ned_in_map_rotation, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock)