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

Private Attributes

ros::NodeHandle node_
 Internal reference to ros::Node.
ros::Publisher publisher_
std::string tf_prefix_

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 55 of file transform_broadcaster.h.


Constructor & Destructor Documentation

tf::TransformBroadcaster::TransformBroadcaster (  ) 

Constructor (needs a ros::Node reference).

Definition at line 40 of file transform_broadcaster.cpp.


Member Function Documentation

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 geometry_msgs::TransformStamped &  transform  ) 

Send a TransformStamped message The stamped data structure includes frame_id, and time, and parent_id already.

Definition at line 47 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 74 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.


Member Data Documentation

ros::NodeHandle tf::TransformBroadcaster::node_ [private]

Internal reference to ros::Node.

Definition at line 78 of file transform_broadcaster.h.

ros::Publisher tf::TransformBroadcaster::publisher_ [private]

Definition at line 79 of file transform_broadcaster.h.

std::string tf::TransformBroadcaster::tf_prefix_ [private]

Definition at line 81 of file transform_broadcaster.h.


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


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Jan 11 09:09:56 2013