Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
tf2::BufferServer Class Reference

#include <buffer_server.h>

List of all members.

Classes

struct  GoalInfo

Public Member Functions

 BufferServer (const Buffer &buffer, const std::string &ns, bool auto_start=false, ros::Duration check_period=ros::Duration(0.01))
void start ()

Private Types

typedef
LookupTransformServer::GoalHandle 
GoalHandle
typedef
actionlib::ActionServer
< tf2_msgs::LookupTransformAction > 
LookupTransformServer

Private Member Functions

void cancelCB (GoalHandle gh)
bool canTransform (GoalHandle gh)
void checkTransforms (const ros::TimerEvent &e)
void goalCB (GoalHandle gh)
geometry_msgs::TransformStamped lookupTransform (GoalHandle gh)

Private Attributes

std::list< GoalInfoactive_goals_
const Bufferbuffer_
ros::Timer check_timer_
boost::mutex mutex_
LookupTransformServer server_

Detailed Description

Definition at line 47 of file buffer_server.h.


Member Typedef Documentation

Definition at line 51 of file buffer_server.h.

typedef actionlib::ActionServer<tf2_msgs::LookupTransformAction> tf2::BufferServer::LookupTransformServer [private]

Definition at line 50 of file buffer_server.h.


Constructor & Destructor Documentation

tf2::BufferServer::BufferServer ( const Buffer buffer,
const std::string &  ns,
bool  auto_start = false,
ros::Duration  check_period = ros::Duration(0.01) 
)

Definition at line 41 of file buffer_server.cpp.


Member Function Documentation

void tf2::BufferServer::cancelCB ( GoalHandle  gh) [private]

Definition at line 113 of file buffer_server.cpp.

Definition at line 192 of file buffer_server.cpp.

void tf2::BufferServer::checkTransforms ( const ros::TimerEvent e) [private]

Definition at line 53 of file buffer_server.cpp.

void tf2::BufferServer::goalCB ( GoalHandle  gh) [private]

Definition at line 133 of file buffer_server.cpp.

geometry_msgs::TransformStamped tf2::BufferServer::lookupTransform ( GoalHandle  gh) [private]

Definition at line 204 of file buffer_server.cpp.

Definition at line 216 of file buffer_server.cpp.


Member Data Documentation

Definition at line 74 of file buffer_server.h.

Definition at line 72 of file buffer_server.h.

Definition at line 76 of file buffer_server.h.

boost::mutex tf2::BufferServer::mutex_ [private]

Definition at line 75 of file buffer_server.h.

Definition at line 73 of file buffer_server.h.


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


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 6 2014 00:12:49