#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)) | |
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< GoalInfo > | active_goals_ |
const Buffer & | buffer_ |
ros::Timer | check_timer_ |
boost::mutex | mutex_ |
LookupTransformServer | server_ |
Definition at line 45 of file buffer_server.h.
typedef LookupTransformServer::GoalHandle tf2::BufferServer::GoalHandle [private] |
Definition at line 47 of file buffer_server.h.
typedef actionlib::ActionServer<tf2_msgs::LookupTransformAction> tf2::BufferServer::LookupTransformServer [private] |
Definition at line 46 of file buffer_server.h.
tf2::BufferServer::BufferServer | ( | const Buffer & | buffer, | |
const std::string & | ns, | |||
bool | auto_start = true , |
|||
ros::Duration | check_period = ros::Duration(0.01) | |||
) |
Definition at line 39 of file buffer_server.cpp.
void tf2::BufferServer::cancelCB | ( | GoalHandle | gh | ) | [private] |
Definition at line 111 of file buffer_server.cpp.
bool tf2::BufferServer::canTransform | ( | GoalHandle | gh | ) | [private] |
Definition at line 190 of file buffer_server.cpp.
void tf2::BufferServer::checkTransforms | ( | const ros::TimerEvent & | e | ) | [private] |
Definition at line 51 of file buffer_server.cpp.
void tf2::BufferServer::goalCB | ( | GoalHandle | gh | ) | [private] |
Definition at line 131 of file buffer_server.cpp.
geometry_msgs::TransformStamped tf2::BufferServer::lookupTransform | ( | GoalHandle | gh | ) | [private] |
Definition at line 202 of file buffer_server.cpp.
void tf2::BufferServer::start | ( | ) |
Definition at line 214 of file buffer_server.cpp.
std::list<GoalInfo> tf2::BufferServer::active_goals_ [private] |
Definition at line 70 of file buffer_server.h.
const Buffer& tf2::BufferServer::buffer_ [private] |
Definition at line 68 of file buffer_server.h.
ros::Timer tf2::BufferServer::check_timer_ [private] |
Definition at line 72 of file buffer_server.h.
boost::mutex tf2::BufferServer::mutex_ [private] |
Definition at line 71 of file buffer_server.h.
Definition at line 69 of file buffer_server.h.