Public Member Functions | Private Attributes | List of all members
tf2_ros::StaticTransformBroadcaster Class Reference

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 <static_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 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...
 
 StaticTransformBroadcaster ()
 Constructor (needs a ros::Node reference) More...
 

Private Attributes

tf2_msgs::TFMessage net_message_
 
ros::NodeHandle node_
 Internal reference to ros::Node. More...
 
ros::Publisher publisher_
 

Detailed Description

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 static_transform_broadcaster.h.

Constructor & Destructor Documentation

◆ StaticTransformBroadcaster()

tf2_ros::StaticTransformBroadcaster::StaticTransformBroadcaster ( )

Constructor (needs a ros::Node reference)

Definition at line 40 of file static_transform_broadcaster.cpp.

Member Function Documentation

◆ sendTransform() [1/2]

void tf2_ros::StaticTransformBroadcaster::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 45 of file static_transform_broadcaster.cpp.

◆ sendTransform() [2/2]

void tf2_ros::StaticTransformBroadcaster::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 53 of file static_transform_broadcaster.cpp.

Member Data Documentation

◆ net_message_

tf2_msgs::TFMessage tf2_ros::StaticTransformBroadcaster::net_message_
private

Definition at line 67 of file static_transform_broadcaster.h.

◆ node_

ros::NodeHandle tf2_ros::StaticTransformBroadcaster::node_
private

Internal reference to ros::Node.

Definition at line 65 of file static_transform_broadcaster.h.

◆ publisher_

ros::Publisher tf2_ros::StaticTransformBroadcaster::publisher_
private

Definition at line 66 of file static_transform_broadcaster.h.


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


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Jun 27 2022 02:43:12