Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
tf2_ros::BufferServer Class Reference

Action server for the actionlib-based implementation of tf2_ros::BufferInterface. More...

#include <buffer_server.h>

Classes

struct  GoalInfo
 

Public Member Functions

 BufferServer (const Buffer &buffer, const std::string &ns, bool auto_start=true, ros::Duration check_period=ros::Duration(0.01))
 Constructor. More...
 
void start ()
 Start the action server. More...
 

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

Action server for the actionlib-based implementation of tf2_ros::BufferInterface.

Use this class with a tf2_ros::TransformListener in the same process. You can use this class with a tf2_ros::BufferClient in a different process.

Definition at line 52 of file buffer_server.h.

Member Typedef Documentation

Definition at line 56 of file buffer_server.h.

typedef actionlib::ActionServer<tf2_msgs::LookupTransformAction> tf2_ros::BufferServer::LookupTransformServer
private

Definition at line 55 of file buffer_server.h.

Constructor & Destructor Documentation

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

Constructor.

Parameters
bufferThe Buffer that this BufferServer will wrap.
nsThe namespace in which to look for action clients.
auto_startPass argument to the constructor of the ActionServer.
check_periodHow often to check for changes to known transforms (via a timer event).

Definition at line 41 of file buffer_server.cpp.

Member Function Documentation

void tf2_ros::BufferServer::cancelCB ( GoalHandle  gh)
private

Definition at line 114 of file buffer_server.cpp.

bool tf2_ros::BufferServer::canTransform ( GoalHandle  gh)
private

Definition at line 193 of file buffer_server.cpp.

void tf2_ros::BufferServer::checkTransforms ( const ros::TimerEvent e)
private

Definition at line 53 of file buffer_server.cpp.

void tf2_ros::BufferServer::goalCB ( GoalHandle  gh)
private

Definition at line 134 of file buffer_server.cpp.

geometry_msgs::TransformStamped tf2_ros::BufferServer::lookupTransform ( GoalHandle  gh)
private

Definition at line 205 of file buffer_server.cpp.

void tf2_ros::BufferServer::start ( )

Start the action server.

Definition at line 217 of file buffer_server.cpp.

Member Data Documentation

std::list<GoalInfo> tf2_ros::BufferServer::active_goals_
private

Definition at line 87 of file buffer_server.h.

const Buffer& tf2_ros::BufferServer::buffer_
private

Definition at line 85 of file buffer_server.h.

ros::Timer tf2_ros::BufferServer::check_timer_
private

Definition at line 89 of file buffer_server.h.

boost::mutex tf2_ros::BufferServer::mutex_
private

Definition at line 88 of file buffer_server.h.

LookupTransformServer tf2_ros::BufferServer::server_
private

Definition at line 86 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 Fri Oct 16 2020 19:08:54