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.hpp
Go to the documentation of this file.
1#pragma once
2/*
3 * Copyright (C) 2019-2020 LEIDOS.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
6 * use this file except in compliance with the License. You may obtain a copy of
7 * the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
13 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
14 * License for the specific language governing permissions and limitations under
15 * the License.
16 */
17
18#include <rclcpp/rclcpp.hpp>
19#include <geometry_msgs/msg/pose_stamped.hpp>
20#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
21#include <geometry_msgs/msg/pose.hpp>
22#include <geometry_msgs/msg/transform_stamped.hpp>
23#include <geometry_msgs/msg/transform.hpp>
24#include <functional>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
27
28namespace pose_to_tf
29{
34{
35public:
36 using TransformPublisher = std::function<void(const geometry_msgs::msg::TransformStamped&)>;
37
43 PoseToTF2(PoseToTF2Config config, TransformPublisher transform_pub,std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> node);
44
50 void poseStampedCallback(geometry_msgs::msg::PoseStamped::UniquePtr msg);
51
57 void poseWithCovarianceStampedCallback(geometry_msgs::msg::PoseWithCovarianceStamped::UniquePtr msg);
58
64 void poseCallback(geometry_msgs::msg::Pose::UniquePtr msg);
65
71 void poseWithCovarianceCallback(geometry_msgs::msg::PoseWithCovariance::UniquePtr msg);
72
73private:
74
75 std::shared_ptr <carma_ros2_utils::CarmaLifecycleNode> node_;
76
79};
80}//namespace pose_to_tf
Primary logic class for the PoseToTF2 node.
Definition: PoseToTF2.hpp:34
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
Stuct containing the frame configuration values for pose_to_tf.