#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 47 of file buffer_server.h.
typedef LookupTransformServer::GoalHandle tf2_ros::BufferServer::GoalHandle [private] |
Definition at line 51 of file buffer_server.h.
typedef actionlib::ActionServer<tf2_msgs::LookupTransformAction> tf2_ros::BufferServer::LookupTransformServer [private] |
Definition at line 50 of file buffer_server.h.
tf2_ros::BufferServer::BufferServer | ( | const Buffer & | buffer, |
const std::string & | ns, | ||
bool | auto_start = true , |
||
ros::Duration | check_period = ros::Duration(0.01) |
||
) |
Definition at line 41 of file buffer_server.cpp.
void tf2_ros::BufferServer::cancelCB | ( | GoalHandle | gh | ) | [private] |
Definition at line 113 of file buffer_server.cpp.
bool tf2_ros::BufferServer::canTransform | ( | GoalHandle | gh | ) | [private] |
Definition at line 192 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 133 of file buffer_server.cpp.
geometry_msgs::TransformStamped tf2_ros::BufferServer::lookupTransform | ( | GoalHandle | gh | ) | [private] |
Definition at line 204 of file buffer_server.cpp.
void tf2_ros::BufferServer::start | ( | ) |
Definition at line 216 of file buffer_server.cpp.
std::list<GoalInfo> tf2_ros::BufferServer::active_goals_ [private] |
Definition at line 74 of file buffer_server.h.
const Buffer& tf2_ros::BufferServer::buffer_ [private] |
Definition at line 72 of file buffer_server.h.
Definition at line 76 of file buffer_server.h.
boost::mutex tf2_ros::BufferServer::mutex_ [private] |
Definition at line 75 of file buffer_server.h.
Definition at line 73 of file buffer_server.h.