43 check_frequency_(check_frequency),
44 timeout_padding_(timeout_padding)
52 tf2_msgs::LookupTransformGoal goal;
53 goal.target_frame = target_frame;
54 goal.source_frame = source_frame;
55 goal.source_time = time;
56 goal.timeout = timeout;
57 goal.advanced =
false;
63 const std::string& source_frame,
const ros::Time& source_time,
64 const std::string& fixed_frame,
const ros::Duration timeout)
const 67 tf2_msgs::LookupTransformGoal goal;
68 goal.target_frame = target_frame;
69 goal.source_frame = source_frame;
70 goal.source_time = source_time;
71 goal.timeout = timeout;
72 goal.target_time = target_time;
73 goal.fixed_frame = fixed_frame;
83 bool timed_out =
false;
96 throw tf2::TimeoutException(
"The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server.");
100 throw tf2::TimeoutException(
"The LookupTransform goal sent to the BufferServer did not come back with SUCCEEDED status. Something is likely wrong with the server.");
109 if(result.error.error != result.error.NO_ERROR){
111 if(result.error.error == result.error.LOOKUP_ERROR)
114 if(result.error.error == result.error.CONNECTIVITY_ERROR)
117 if(result.error.error == result.error.EXTRAPOLATION_ERROR)
120 if(result.error.error == result.error.INVALID_ARGUMENT_ERROR)
123 if(result.error.error == result.error.TIMEOUT_ERROR)
129 return result.transform;
152 const std::string& source_frame,
const ros::Time& source_time,
153 const std::string& fixed_frame,
const ros::Duration timeout, std::string* errstr)
const 157 lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout);
ros::Duration timeout_padding_
LookupActionClient client_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal &goal) const
BufferClient(std::string ns, double check_frequency=10.0, ros::Duration timeout_padding=ros::Duration(2.0))
BufferClient constructor.
SimpleClientGoalState getState() const
ResultConstPtr getResult() const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout=ros::Duration(0.0)) const
Get the transform between two frames by frame ID.
geometry_msgs::TransformStamped processResult(const tf2_msgs::LookupTransformResult &result) const
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout=ros::Duration(0.0), std::string *errstr=NULL) const
Test if a transform is possible.