18#include <rclcpp/rclcpp.hpp>
19#include <tf2_ros/transform_broadcaster.h>
22#include <carma_ros2_utils/carma_lifecycle_node.hpp>
37 carma_ros2_utils::SubPtr<geometry_msgs::msg::Pose>
pose_sub;
The class is responsible for processing pose to tf conversion.
std::shared_ptr< PoseToTF2 > pose_to_tf_worker_
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseWithCovarianceStamped > pose_with_cov_stamped_sub
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseWithCovariance > pose_with_cov_sub
PoseToTfNode(const rclcpp::NodeOptions &)
PoseToTfNode constructor.
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_stamped_sub
carma_ros2_utils::SubPtr< geometry_msgs::msg::Pose > pose_sub
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
Stuct containing the frame configuration values for pose_to_tf.