static_transform_broadcaster::StaticTransformBroadcaster Class Reference

Continuously re-publishes passed in transforms. More...

#include <static_transform_broadcaster.h>

List of all members.

Public Member Functions

double getPublishingRate () const
void removeAllTransforms ()
 Removes all transforms from the list.
void removeTransform (std::string child_frame_id)
 Removes a transform from the list, based on teh child_frame_id.
void setPublishingRate (double rate)
 Sets the publishing rate. If passed value is negative, 0.0 is used instead.
void setTransform (geometry_msgs::TransformStamped transform)
 Add a transform to the list or change an existing one.
 StaticTransformBroadcaster ()
 Starts the publishing thread.
 ~StaticTransformBroadcaster ()
 Stops and joins the publishing thread.

Private Member Functions

void publishingThread ()

Private Attributes

tf::TransformBroadcaster broadcaster_
 The broadcaster used.
bool finished_
 Internal flag showing the instance is being destructed.
boost::mutex mutex_
 Mutex for access control.
double publishing_rate_
 The broadcast rate, in seconds.
boost::thread * publishing_thread_
 The thread used for publishing.
std::map< std::string,
geometry_msgs::TransformStamped > 
transforms_
 The internal list of transforms to be broadcast.

Detailed Description

Continuously re-publishes passed in transforms.

Used to keep in the system transforms that do not change often, but nobody wants to keep re-publishing. Just pass a transform to this class and it will keep republishing it for you until you remove it.

Transforms are uniquely identified by their child_frame_id. If a passed in transform has the same child_frame_id as an existing one, the old one is replaced by the new one.

The re-publishing is done at a constant rate which can be modified.

Definition at line 57 of file static_transform_broadcaster.h.


Constructor & Destructor Documentation

static_transform_broadcaster::StaticTransformBroadcaster::StaticTransformBroadcaster (  )  [inline]

Starts the publishing thread.

Definition at line 86 of file static_transform_broadcaster.h.

static_transform_broadcaster::StaticTransformBroadcaster::~StaticTransformBroadcaster (  )  [inline]

Stops and joins the publishing thread.

Definition at line 92 of file static_transform_broadcaster.h.


Member Function Documentation

double static_transform_broadcaster::StaticTransformBroadcaster::getPublishingRate (  )  const [inline]

Definition at line 137 of file static_transform_broadcaster.h.

void static_transform_broadcaster::StaticTransformBroadcaster::publishingThread (  )  [inline, private]

Does all the publishing work. Broadcasts all transforms with a time stamp of ros::Time::now() then sleeps for the duration equal to the publishing rate

Definition at line 67 of file static_transform_broadcaster.h.

void static_transform_broadcaster::StaticTransformBroadcaster::removeAllTransforms (  )  [inline]

Removes all transforms from the list.

Definition at line 126 of file static_transform_broadcaster.h.

void static_transform_broadcaster::StaticTransformBroadcaster::removeTransform ( std::string  child_frame_id  )  [inline]

Removes a transform from the list, based on teh child_frame_id.

Definition at line 109 of file static_transform_broadcaster.h.

void static_transform_broadcaster::StaticTransformBroadcaster::setPublishingRate ( double  rate  )  [inline]

Sets the publishing rate. If passed value is negative, 0.0 is used instead.

Definition at line 132 of file static_transform_broadcaster.h.

void static_transform_broadcaster::StaticTransformBroadcaster::setTransform ( geometry_msgs::TransformStamped  transform  )  [inline]

Add a transform to the list or change an existing one.

If a transform already exists with the same child_frame_id, it is replaced by this new transform

Definition at line 101 of file static_transform_broadcaster.h.


Member Data Documentation

The broadcaster used.

Definition at line 48 of file static_transform_broadcaster.h.

Internal flag showing the instance is being destructed.

Definition at line 57 of file static_transform_broadcaster.h.

Mutex for access control.

Definition at line 63 of file static_transform_broadcaster.h.

The broadcast rate, in seconds.

Definition at line 54 of file static_transform_broadcaster.h.

The thread used for publishing.

Definition at line 60 of file static_transform_broadcaster.h.

std::map<std::string, geometry_msgs::TransformStamped> static_transform_broadcaster::StaticTransformBroadcaster::transforms_ [private]

The internal list of transforms to be broadcast.

Definition at line 51 of file static_transform_broadcaster.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs


static_transform_broadcaster
Author(s): Matei Ciocarlie
autogenerated on Fri Jan 11 09:14:08 2013