43 server_(
ros::NodeHandle(),
56 boost::mutex::scoped_lock l(
mutex_);
65 tf2_msgs::LookupTransformResult result;
74 result.error.error = result.error.CONNECTIVITY_ERROR;
75 result.error.error_string = ex.what();
79 result.error.error = result.error.LOOKUP_ERROR;
80 result.error.error_string = ex.what();
84 result.error.error = result.error.EXTRAPOLATION_ERROR;
85 result.error.error_string = ex.what();
89 result.error.error = result.error.INVALID_ARGUMENT_ERROR;
90 result.error.error_string = ex.what();
94 result.error.error = result.error.TIMEOUT_ERROR;
95 result.error.error_string = ex.what();
99 result.error.error = result.error.TRANSFORM_ERROR;
100 result.error.error_string = ex.what();
116 boost::mutex::scoped_lock l(
mutex_);
149 tf2_msgs::LookupTransformResult result;
156 result.error.error = result.error.CONNECTIVITY_ERROR;
157 result.error.error_string = ex.what();
161 result.error.error = result.error.LOOKUP_ERROR;
162 result.error.error_string = ex.what();
166 result.error.error = result.error.EXTRAPOLATION_ERROR;
167 result.error.error_string = ex.what();
171 result.error.error = result.error.INVALID_ARGUMENT_ERROR;
172 result.error.error_string = ex.what();
176 result.error.error = result.error.TIMEOUT_ERROR;
177 result.error.error_string = ex.what();
181 result.error.error = result.error.TRANSFORM_ERROR;
182 result.error.error_string = ex.what();
189 boost::mutex::scoped_lock l(
mutex_);
195 const tf2_msgs::LookupTransformGoal::ConstPtr& goal = gh.
getGoal();
202 goal->source_frame, goal->source_time, goal->fixed_frame);
207 const tf2_msgs::LookupTransformGoal::ConstPtr& goal = gh.
getGoal();
214 goal->source_frame, goal->source_time, goal->fixed_frame);
void checkTransforms(const ros::TimerEvent &e)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
Get the transform between two frames by frame ID.
boost::shared_ptr< const Goal > getGoal() const
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Action server for the actionlib-based implementation of tf2_ros::BufferInterface. ...
bool canTransform(GoalHandle gh)
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
void setAccepted(const std::string &text=std::string(""))
LookupTransformServer server_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
geometry_msgs::TransformStamped lookupTransform(GoalHandle gh)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void goalCB(GoalHandle gh)
void start()
Start the action server.
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
Test if a transform is possible.
BufferServer(const Buffer &buffer, const std::string &ns, bool auto_start=true, ros::Duration check_period=ros::Duration(0.01))
Constructor.
std::list< GoalInfo > active_goals_
void cancelCB(GoalHandle gh)