This class provides an easy way to publish coordinate frame transform information.
It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message.
More...
#include <transform_broadcaster.h>
Public Member Functions | |
void | sendTransform (const geometry_msgs::TransformStamped &transform) |
Send a TransformStamped message The stamped data structure includes frame_id, and time, and parent_id already. More... | |
void | sendTransform (const StampedTransform &transform) |
Send a StampedTransform The stamped data structure includes frame_id, and time, and parent_id already. More... | |
void | sendTransform (const std::vector< geometry_msgs::TransformStamped > &transforms) |
Send a vector of TransformStamped messages The stamped data structure includes frame_id, and time, and parent_id already. More... | |
void | sendTransform (const std::vector< StampedTransform > &transforms) |
Send a vector of StampedTransforms The stamped data structure includes frame_id, and time, and parent_id already. More... | |
TransformBroadcaster () | |
Constructor (needs a ros::Node reference) More... | |
Private Attributes | |
tf2_ros::TransformBroadcaster | tf2_broadcaster_ |
This class provides an easy way to publish coordinate frame transform information.
It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message.
Definition at line 50 of file transform_broadcaster.h.
tf::TransformBroadcaster::TransformBroadcaster | ( | ) |
Constructor (needs a ros::Node reference)
Definition at line 44 of file transform_broadcaster.cpp.
void tf::TransformBroadcaster::sendTransform | ( | const geometry_msgs::TransformStamped & | transform | ) |
Send a TransformStamped message The stamped data structure includes frame_id, and time, and parent_id already.
Definition at line 49 of file transform_broadcaster.cpp.
void tf::TransformBroadcaster::sendTransform | ( | const StampedTransform & | transform | ) |
Send a StampedTransform The stamped data structure includes frame_id, and time, and parent_id already.
Definition at line 54 of file transform_broadcaster.cpp.
void tf::TransformBroadcaster::sendTransform | ( | const std::vector< geometry_msgs::TransformStamped > & | transforms | ) |
Send a vector of TransformStamped messages The stamped data structure includes frame_id, and time, and parent_id already.
Definition at line 61 of file transform_broadcaster.cpp.
void tf::TransformBroadcaster::sendTransform | ( | const std::vector< StampedTransform > & | transforms | ) |
Send a vector of StampedTransforms The stamped data structure includes frame_id, and time, and parent_id already.
Definition at line 66 of file transform_broadcaster.cpp.
|
private |
Definition at line 73 of file transform_broadcaster.h.