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.
pose_to_tf::PoseToTfNode Class Reference

The class is responsible for processing pose to tf conversion.
More...

#include <PoseToTF2Node.hpp>

Inheritance diagram for pose_to_tf::PoseToTfNode:
Inheritance graph
Collaboration diagram for pose_to_tf::PoseToTfNode:
Collaboration graph

Public Member Functions

 PoseToTfNode (const rclcpp::NodeOptions &)
 PoseToTfNode constructor. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 

Private Attributes

carma_ros2_utils::SubPtr< geometry_msgs::msg::Pose > pose_sub
 
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_stamped_sub
 
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseWithCovariance > pose_with_cov_sub
 
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseWithCovarianceStamped > pose_with_cov_stamped_sub
 
std::shared_ptr< PoseToTF2pose_to_tf_worker_
 
PoseToTF2Config config_
 

Detailed Description

The class is responsible for processing pose to tf conversion.

Definition at line 32 of file PoseToTF2Node.hpp.

Constructor & Destructor Documentation

◆ PoseToTfNode()

pose_to_tf::PoseToTfNode::PoseToTfNode ( const rclcpp::NodeOptions &  options)
explicit

PoseToTfNode constructor.

Definition at line 24 of file PoseToTF2Node.cpp.

25 : carma_ros2_utils::CarmaLifecycleNode(options)
26 {
27 // Create initial config
28 config_ = PoseToTF2Config();
29
30 // Declare parameters
31 config_.child_frame = declare_parameter<std::string>("message_type", config_.child_frame);
32 config_.default_parent_frame = declare_parameter<std::string>("target_frame", config_.default_parent_frame);
33 }

References pose_to_tf::PoseToTF2Config::child_frame, config_, and pose_to_tf::PoseToTF2Config::default_parent_frame.

Member Function Documentation

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn pose_to_tf::PoseToTfNode::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 35 of file PoseToTF2Node.cpp.

36 {
37 tf2_ros::TransformBroadcaster tf_broadcaster(shared_from_this());
38 pose_to_tf::PoseToTF2 worker(config_, [&tf_broadcaster](auto msg){tf_broadcaster.sendTransform(msg);}, shared_from_this());
39 pose_to_tf_worker_= std::make_shared<PoseToTF2>(worker);
40
41 // Setup subscribers
42 pose_sub = create_subscription<geometry_msgs::msg::Pose>("pose_to_tf", 50,
43 std::bind(&pose_to_tf::PoseToTF2::poseCallback, pose_to_tf_worker_.get(), std_ph::_1));
44 pose_stamped_sub = create_subscription<geometry_msgs::msg::PoseStamped>("pose_stamped_to_tf", 50,
46 pose_with_cov_sub = create_subscription<geometry_msgs::msg::PoseWithCovariance>("pose_with_cov_to_tf", 50,
48 pose_with_cov_stamped_sub = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>("pose_with_cov_stamped_to_tf", 50,
50
51 // Return success if everthing initialized successfully
52 return CallbackReturn::SUCCESS;
53 }
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
void poseWithCovarianceStampedCallback(geometry_msgs::msg::PoseWithCovarianceStamped::UniquePtr msg)
Callback for new pose stamped messages.
Definition: PoseToTF2.cpp:73
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
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
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_stamped_sub
carma_ros2_utils::SubPtr< geometry_msgs::msg::Pose > pose_sub

References config_, pose_stamped_sub, pose_sub, pose_to_tf_worker_, pose_with_cov_stamped_sub, pose_with_cov_sub, pose_to_tf::PoseToTF2::poseCallback(), pose_to_tf::PoseToTF2::poseStampedCallback(), pose_to_tf::PoseToTF2::poseWithCovarianceCallback(), and pose_to_tf::PoseToTF2::poseWithCovarianceStampedCallback().

Here is the call graph for this function:

Member Data Documentation

◆ config_

PoseToTF2Config pose_to_tf::PoseToTfNode::config_
private

Definition at line 46 of file PoseToTF2Node.hpp.

Referenced by PoseToTfNode(), and handle_on_configure().

◆ pose_stamped_sub

carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> pose_to_tf::PoseToTfNode::pose_stamped_sub
private

Definition at line 38 of file PoseToTF2Node.hpp.

Referenced by handle_on_configure().

◆ pose_sub

carma_ros2_utils::SubPtr<geometry_msgs::msg::Pose> pose_to_tf::PoseToTfNode::pose_sub
private

Definition at line 37 of file PoseToTF2Node.hpp.

Referenced by handle_on_configure().

◆ pose_to_tf_worker_

std::shared_ptr<PoseToTF2> pose_to_tf::PoseToTfNode::pose_to_tf_worker_
private

Definition at line 43 of file PoseToTF2Node.hpp.

Referenced by handle_on_configure().

◆ pose_with_cov_stamped_sub

carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseWithCovarianceStamped> pose_to_tf::PoseToTfNode::pose_with_cov_stamped_sub
private

Definition at line 40 of file PoseToTF2Node.hpp.

Referenced by handle_on_configure().

◆ pose_with_cov_sub

carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseWithCovariance> pose_to_tf::PoseToTfNode::pose_with_cov_sub
private

Definition at line 39 of file PoseToTF2Node.hpp.

Referenced by handle_on_configure().


The documentation for this class was generated from the following files: