15#ifndef MOTION_COMPUTATION__IMPL__MOBILITY_PATH_TO_EXTERNAL_OBJECT_HELPERS_HPP_
16#define MOTION_COMPUTATION__IMPL__MOBILITY_PATH_TO_EXTERNAL_OBJECT_HELPERS_HPP_
18#include <lanelet2_extension/projection/local_frame_projector.h>
19#include <tf2/LinearMath/Quaternion.h>
20#include <tf2/LinearMath/Vector3.h>
25#include <rclcpp/time.hpp>
27#include <carma_perception_msgs/msg/external_object.hpp>
28#include <carma_perception_msgs/msg/predicted_state.hpp>
29#include <geometry_msgs/msg/quaternion.hpp>
51 const tf2::Vector3 & curr_pt,
const tf2::Vector3 & prev_pt,
const rclcpp::Time & prev_time_stamp,
52 const rclcpp::Time & curr_time_stamp,
double prev_yaw);
74 const tf2::Vector3 & ecef_point,
const lanelet::projection::LocalFrameProjector & map_projector);
double getYawFromQuaternionMsg(const geometry_msgs::msg::Quaternion &quaternion)
Gets the yaw angle in degrees described by the provided quaternion.
tf2::Vector3 transform_to_map_frame(const tf2::Vector3 &ecef_point, const lanelet::projection::LocalFrameProjector &map_projector)
Transforms ecef point to map frame using internally saved map transform.
void calculateAngVelocityOfPredictedStates(carma_perception_msgs::msg::ExternalObject &object)
Helper function to fill in the angular velocity of the external object.
std::pair< carma_perception_msgs::msg::PredictedState, double > composePredictedState(const tf2::Vector3 &curr_pt, const tf2::Vector3 &prev_pt, const rclcpp::Time &prev_time_stamp, const rclcpp::Time &curr_time_stamp, double prev_yaw)
Composes a PredictedState message form a provided current point and previous point....