15#ifndef MOTION_COMPUTATION__IMPL__PSM_TO_EXTERNAL_OBJECT_HELPERS_HPP_
16#define MOTION_COMPUTATION__IMPL__PSM_TO_EXTERNAL_OBJECT_HELPERS_HPP_
18#include <lanelet2_core/primitives/GPSPoint.h>
19#include <lanelet2_extension/projection/local_frame_projector.h>
20#include <tf2/LinearMath/Quaternion.h>
25#include <rclcpp/rclcpp.hpp>
27#include <carma_perception_msgs/msg/external_object.hpp>
28#include <carma_v2x_msgs/msg/psm.hpp>
29#include <geometry_msgs/msg/pose.hpp>
30#include <geometry_msgs/msg/pose_with_covariance.hpp>
41 const geometry_msgs::msg::Pose & pose,
double velocity,
double radius_of_curvature,
double period,
45 const geometry_msgs::msg::Pose & pose,
double velocity,
double period,
double step_size);
48 const lanelet::projection::LocalFrameProjector & projector,
49 const tf2::Quaternion & ned_in_map_rotation,
const lanelet::GPSPoint & gps_point,
50 const double & heading,
const double lat_variance,
const double lon_variance,
51 const double heading_variance);
55 const std::vector<geometry_msgs::msg::Pose> & poses,
double constant_velocity,
56 const rclcpp::Time & start_time,
const rclcpp::Duration & step_size,
const std::string & frame,
57 double initial_pose_confidence,
double initial_vel_confidence);
60 const carma_v2x_msgs::msg::PSM & in_msg, rclcpp::Clock::SharedPtr clock);
std::vector< geometry_msgs::msg::Pose > sample_2d_path_from_radius(const geometry_msgs::msg::Pose &pose, double velocity, double radius_of_curvature, double period, double step_size)
geometry_msgs::msg::PoseWithCovariance pose_from_gnss(const lanelet::projection::LocalFrameProjector &projector, const tf2::Quaternion &ned_in_map_rotation, const lanelet::GPSPoint &gps_point, const double &heading, const double lat_variance, const double lon_variance, const double heading_variance)
std::vector< carma_perception_msgs::msg::PredictedState > predicted_poses_to_predicted_state(const std::vector< geometry_msgs::msg::Pose > &poses, double constant_velocity, const rclcpp::Time &start_time, const rclcpp::Duration &step_size, const std::string &frame, double initial_pose_confidence, double initial_vel_confidence)
rclcpp::Time get_psm_timestamp(const carma_v2x_msgs::msg::PSM &in_msg, rclcpp::Clock::SharedPtr clock)
std::vector< geometry_msgs::msg::Pose > sample_2d_linear_motion(const geometry_msgs::msg::Pose &pose, double velocity, double period, double step_size)