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.
psm_to_external_object_helpers.hpp
Go to the documentation of this file.
1// Copyright 2020-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
15#ifndef MOTION_COMPUTATION__IMPL__PSM_TO_EXTERNAL_OBJECT_HELPERS_HPP_
16#define MOTION_COMPUTATION__IMPL__PSM_TO_EXTERNAL_OBJECT_HELPERS_HPP_
17
18#include <lanelet2_core/primitives/GPSPoint.h>
19#include <lanelet2_extension/projection/local_frame_projector.h>
20#include <tf2/LinearMath/Quaternion.h>
21
22#include <string>
23#include <vector>
24
25#include <rclcpp/rclcpp.hpp>
26
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>
31
32namespace motion_computation
33{
34namespace conversion
35{
36// Namespace for functionality not meant to be part of public API but valuable
37// to unit test in isolation
38namespace impl
39{
40std::vector<geometry_msgs::msg::Pose> sample_2d_path_from_radius(
41 const geometry_msgs::msg::Pose & pose, double velocity, double radius_of_curvature, double period,
42 double step_size);
43
44std::vector<geometry_msgs::msg::Pose> sample_2d_linear_motion(
45 const geometry_msgs::msg::Pose & pose, double velocity, double period, double step_size);
46
47geometry_msgs::msg::PoseWithCovariance pose_from_gnss(
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);
52
53std::vector<carma_perception_msgs::msg::PredictedState> predicted_poses_to_predicted_state(
54
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);
58
59rclcpp::Time get_psm_timestamp(
60 const carma_v2x_msgs::msg::PSM & in_msg, rclcpp::Clock::SharedPtr clock);
61
62} // namespace impl
63} // namespace conversion
64} // namespace motion_computation
65
66#endif // MOTION_COMPUTATION__IMPL__PSM_TO_EXTERNAL_OBJECT_HELPERS_HPP_
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)