37 #ifndef TF2_ROS_BUFFER_CLIENT_H_
38 #define TF2_ROS_BUFFER_CLIENT_H_
40 #include <rclcpp_action/rclcpp_action.hpp>
41 #include <tf2_msgs/action/lookup_transform.hpp>
61 class GoalRejectedException :
public LookupTransformGoalException
71 class GoalAbortedException :
public LookupTransformGoalException
81 class GoalCanceledException :
public LookupTransformGoalException
91 class UnexpectedResultCodeException :
public LookupTransformGoalException
118 template<
typename NodePtr>
122 const double& check_frequency = 10.0,
123 const tf2::Duration& timeout_padding = tf2::durationFromSec(2.0))
124 : check_frequency_(check_frequency),
125 timeout_padding_(timeout_padding)
127 client_ = rclcpp_action::create_client<LookupTransformAction>(node, ns);
154 geometry_msgs::msg::TransformStamped
158 const tf2::TimePoint& time,
159 const tf2::Duration timeout = tf2::durationFromSec(0.0))
const override;
186 geometry_msgs::msg::TransformStamped
189 const tf2::TimePoint& target_time,
191 const tf2::TimePoint& source_time,
193 const tf2::Duration timeout = tf2::durationFromSec(0.0))
const override;
208 const tf2::TimePoint& time,
209 const tf2::Duration timeout = tf2::durationFromSec(0.0),
226 const tf2::TimePoint& target_time,
228 const tf2::TimePoint& source_time,
230 const tf2::Duration timeout = tf2::durationFromSec(0.0),
238 bool waitForServer(
const tf2::Duration& timeout = tf2::durationFromSec(0))
240 return client_->wait_for_action_server(timeout);
244 geometry_msgs::msg::TransformStamped
245 processGoal(
const LookupTransformAction::Goal& goal)
const;
247 geometry_msgs::msg::TransformStamped
248 processResult(
const LookupTransformAction::Result::SharedPtr& result)
const;
250 rclcpp_action::Client<LookupTransformAction>::SharedPtr client_;
251 double check_frequency_;
252 tf2::Duration timeout_padding_;