tf2::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>

List of all members.

Public Member Functions

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.
void sendTransform (const geometry_msgs::TransformStamped &transform)
 Send a TransformStamped message The stamped data structure includes frame_id, and time, and parent_id already.
 StaticTransformBroadcaster ()
 Constructor (needs a ros::Node reference).

Private Attributes

tf2_msgs::TFMessage net_message_
ros::NodeHandle node_
 Internal reference to ros::Node.
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 48 of file static_transform_broadcaster.h.


Constructor & Destructor Documentation

tf2::StaticTransformBroadcaster::StaticTransformBroadcaster (  ) 

Constructor (needs a ros::Node reference).

Definition at line 39 of file static_transform_broadcaster.cpp.


Member Function Documentation

void tf2::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 52 of file static_transform_broadcaster.cpp.

void tf2::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 44 of file static_transform_broadcaster.cpp.


Member Data Documentation

tf2_msgs::TFMessage tf2::StaticTransformBroadcaster::net_message_ [private]

Definition at line 58 of file static_transform_broadcaster.h.

ros::NodeHandle tf2::StaticTransformBroadcaster::node_ [private]

Internal reference to ros::Node.

Definition at line 56 of file static_transform_broadcaster.h.

Definition at line 57 of file static_transform_broadcaster.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


tf2_ros
Author(s): Wim Meeussen, Eitan Marder-Eppstein
autogenerated on Fri Jan 11 09:59:07 2013