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.
message_conversions.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__MESSAGE_CONVERSIONS_HPP_
16#define MOTION_COMPUTATION__MESSAGE_CONVERSIONS_HPP_
17
18#include <lanelet2_extension/projection/local_frame_projector.h>
19#include <tf2/LinearMath/Quaternion.h>
20
21#include <string>
22
23#include <rclcpp/rclcpp.hpp>
24
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>
29
30namespace motion_computation
31{
32namespace conversion
33{
34void convert(
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);
40
41void convert(
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);
46
47void convert(
48 const carma_v2x_msgs::msg::MobilityPath & in_msg,
49 carma_perception_msgs::msg::ExternalObject & out_msg,
50 const lanelet::projection::LocalFrameProjector & map_projector);
51} // namespace conversion
52} // namespace motion_computation
53
54#endif // MOTION_COMPUTATION__MESSAGE_CONVERSIONS_HPP_
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)