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< GoalInfo > | active_goals_ |
const Buffer & | buffer_ |
ros::Timer | check_timer_ |
boost::mutex | mutex_ |
LookupTransformServer | server_ |
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.
|
private |
Definition at line 56 of file buffer_server.h.
|
private |
Definition at line 55 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) |
||
) |
Constructor.
buffer | The Buffer that this BufferServer will wrap. |
ns | The namespace in which to look for action clients. |
auto_start | Pass argument to the constructor of the ActionServer. |
check_period | How often to check for changes to known transforms (via a timer event). |
Definition at line 41 of file buffer_server.cpp.
|
private |
Definition at line 114 of file buffer_server.cpp.
|
private |
Definition at line 193 of file buffer_server.cpp.
|
private |
Definition at line 53 of file buffer_server.cpp.
|
private |
Definition at line 134 of file buffer_server.cpp.
|
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.
|
private |
Definition at line 87 of file buffer_server.h.
|
private |
Definition at line 85 of file buffer_server.h.
|
private |
Definition at line 89 of file buffer_server.h.
|
private |
Definition at line 88 of file buffer_server.h.
|
private |
Definition at line 86 of file buffer_server.h.