38 #ifndef TF2_ROS__BUFFER_CLIENT_H_
39 #define TF2_ROS__BUFFER_CLIENT_H_
45 #include <geometry_msgs/msg/transform_stamped.hpp>
46 #include <rclcpp_action/rclcpp_action.hpp>
47 #include <tf2_msgs/action/lookup_transform.hpp>
67 class GoalRejectedException :
public LookupTransformGoalException
77 class GoalAbortedException :
public LookupTransformGoalException
87 class GoalCanceledException :
public LookupTransformGoalException
97 class UnexpectedResultCodeException :
public LookupTransformGoalException
124 template<
typename NodePtr>
128 const double & check_frequency = 10.0,
129 const tf2::Duration & timeout_padding = tf2::durationFromSec(2.0))
130 : check_frequency_(check_frequency),
131 timeout_padding_(timeout_padding)
133 client_ = rclcpp_action::create_client<LookupTransformAction>(node, ns);
161 geometry_msgs::msg::TransformStamped
165 const tf2::TimePoint & time,
166 const tf2::Duration timeout = tf2::durationFromSec(0.0))
const override;
193 geometry_msgs::msg::TransformStamped
196 const tf2::TimePoint & target_time,
198 const tf2::TimePoint & source_time,
200 const tf2::Duration timeout = tf2::durationFromSec(0.0))
const override;
215 const tf2::TimePoint & time,
216 const tf2::Duration timeout = tf2::durationFromSec(0.0),
233 const tf2::TimePoint & target_time,
235 const tf2::TimePoint & source_time,
237 const tf2::Duration timeout = tf2::durationFromSec(0.0),
245 bool waitForServer(
const tf2::Duration & timeout = tf2::durationFromSec(0))
247 return client_->wait_for_action_server(timeout);
251 geometry_msgs::msg::TransformStamped
252 processGoal(
const LookupTransformAction::Goal & goal)
const;
254 geometry_msgs::msg::TransformStamped
255 processResult(
const LookupTransformAction::Result::SharedPtr & result)
const;
257 rclcpp_action::Client<LookupTransformAction>::SharedPtr client_;
258 double check_frequency_;
259 tf2::Duration timeout_padding_;
263 #endif // TF2_ROS__BUFFER_CLIENT_H_