Go to the documentation of this file.
37 #ifndef TF2_ROS_BUFFER_SERVER_H_
38 #define TF2_ROS_BUFFER_SERVER_H_
41 #include <tf2_msgs/LookupTransformAction.h>
42 #include <geometry_msgs/TransformStamped.h>
71 BufferServer(
const Buffer& buffer,
const std::string& ns,
std::list< GoalInfo > active_goals_
LookupTransformServer server_
void goalCB(GoalHandle gh)
BufferServer(const Buffer &buffer, const std::string &ns, bool auto_start=true, ros::Duration check_period=ros::Duration(0.01))
Constructor.
bool canTransform(GoalHandle gh)
void cancelCB(GoalHandle gh)
void checkTransforms(const ros::TimerEvent &e)
void start()
Start the action server.
LookupTransformServer::GoalHandle GoalHandle
ServerGoalHandle< ActionSpec > GoalHandle
geometry_msgs::TransformStamped lookupTransform(GoalHandle gh)
actionlib::ActionServer< tf2_msgs::LookupTransformAction > LookupTransformServer
tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:16