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.
PoseToTF2.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2019-2020 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <rclcpp/rclcpp.hpp>
18#include <geometry_msgs/msg/pose_stamped.hpp>
19#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
20#include <geometry_msgs/msg/pose.hpp>
21#include <geometry_msgs/msg/transform_stamped.hpp>
22#include <geometry_msgs/msg/transform.hpp>
23#include <functional>
25
26namespace tf2
27{
28namespace
29{
30void convert(const geometry_msgs::msg::Pose& pose, geometry_msgs::msg::Transform& trans)
31{
32 trans.rotation = pose.orientation;
33 trans.translation.x = pose.position.x;
34 trans.translation.y = pose.position.y;
35 trans.translation.z = pose.position.z;
36}
37
38void convert(const geometry_msgs::msg::PoseWithCovariance& pose, geometry_msgs::msg::Transform& trans)
39{
40 convert(pose.pose, trans);
41}
42
43void convert(const geometry_msgs::msg::PoseStamped& pose, geometry_msgs::msg::TransformStamped& trans)
44{
45 convert(pose.pose, trans.transform);
46 trans.header = pose.header;
47}
48
49void convert(const geometry_msgs::msg::PoseWithCovarianceStamped& pose, geometry_msgs::msg::TransformStamped& trans)
50{
51 convert(pose.pose, trans.transform);
52 trans.header = pose.header;
53}
54} // namespace
55} // namespace tf2
56
57namespace pose_to_tf
58{
59
60PoseToTF2::PoseToTF2(PoseToTF2Config config, TransformPublisher transform_pub, std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> node)
61 : config_(config), transform_pub_(transform_pub), node_(node)
62{
63}
64
65void PoseToTF2::poseStampedCallback(geometry_msgs::msg::PoseStamped::UniquePtr msg)
66{
67 geometry_msgs::msg::TransformStamped out_tf;
68 tf2::convert(*msg, out_tf);
69 out_tf.child_frame_id = config_.child_frame;
70 transform_pub_(out_tf);
71}
72
73void PoseToTF2::poseWithCovarianceStampedCallback(geometry_msgs::msg::PoseWithCovarianceStamped::UniquePtr msg)
74{
75 geometry_msgs::msg::TransformStamped out_tf;
76 tf2::convert(*msg, out_tf);
77 out_tf.child_frame_id = config_.child_frame;
78 transform_pub_(out_tf);
79}
80
81void PoseToTF2::poseCallback(geometry_msgs::msg::Pose::UniquePtr msg)
82{
83 geometry_msgs::msg::TransformStamped out_tf;
84 tf2::convert(*msg, out_tf.transform);
85 out_tf.header.stamp = node_->now();
86 out_tf.header.frame_id = config_.default_parent_frame;
87 out_tf.child_frame_id = config_.child_frame;
88 transform_pub_(out_tf);
89}
90
91void PoseToTF2::poseWithCovarianceCallback(geometry_msgs::msg::PoseWithCovariance::UniquePtr msg)
92{
93 geometry_msgs::msg::TransformStamped out_tf;
94 tf2::convert(*msg, out_tf.transform);
95 out_tf.header.stamp = node_->now();
96 out_tf.header.frame_id = config_.default_parent_frame;
97 out_tf.child_frame_id = config_.child_frame;
98 transform_pub_(out_tf);
99}
100}//namespace pose_to_tf
void poseStampedCallback(geometry_msgs::msg::PoseStamped::UniquePtr msg)
Callback for new pose stamped messages.
Definition: PoseToTF2.cpp:65
PoseToTF2(PoseToTF2Config config, TransformPublisher transform_pub, std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node)
Constructor.
Definition: PoseToTF2.cpp:60
void poseWithCovarianceStampedCallback(geometry_msgs::msg::PoseWithCovarianceStamped::UniquePtr msg)
Callback for new pose stamped messages.
Definition: PoseToTF2.cpp:73
std::function< void(const geometry_msgs::msg::TransformStamped &)> TransformPublisher
Definition: PoseToTF2.hpp:36
void poseWithCovarianceCallback(geometry_msgs::msg::PoseWithCovariance::UniquePtr msg)
Callback for new pose with covariance messages.
Definition: PoseToTF2.cpp:91
void poseCallback(geometry_msgs::msg::Pose::UniquePtr msg)
Callback for new pose stamped messages.
Definition: PoseToTF2.cpp:81
PoseToTF2Config config_
Definition: PoseToTF2.hpp:77
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node_
Definition: PoseToTF2.hpp:75
TransformPublisher transform_pub_
Definition: PoseToTF2.hpp:78
void convert(const geometry_msgs::msg::PoseWithCovarianceStamped &pose, geometry_msgs::msg::TransformStamped &trans)
Definition: PoseToTF2.cpp:49
Stuct containing the frame configuration values for pose_to_tf.