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>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
64 void poseCallback(geometry_msgs::msg::Pose::UniquePtr msg);
75 std::shared_ptr <carma_ros2_utils::CarmaLifecycleNode>
node_;
Primary logic class for the PoseToTF2 node.
void poseStampedCallback(geometry_msgs::msg::PoseStamped::UniquePtr msg)
Callback for new pose stamped messages.
PoseToTF2(PoseToTF2Config config, TransformPublisher transform_pub, std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node)
Constructor.
void poseWithCovarianceStampedCallback(geometry_msgs::msg::PoseWithCovarianceStamped::UniquePtr msg)
Callback for new pose stamped messages.
std::function< void(const geometry_msgs::msg::TransformStamped &)> TransformPublisher
void poseWithCovarianceCallback(geometry_msgs::msg::PoseWithCovariance::UniquePtr msg)
Callback for new pose with covariance messages.
void poseCallback(geometry_msgs::msg::Pose::UniquePtr msg)
Callback for new pose stamped messages.
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node_
TransformPublisher transform_pub_
Stuct containing the frame configuration values for pose_to_tf.