tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
buffer_client.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 
38 #ifndef TF2_ROS__BUFFER_CLIENT_H_
39 #define TF2_ROS__BUFFER_CLIENT_H_
40 
43 #include <tf2/time.h>
44 
45 #include <geometry_msgs/msg/transform_stamped.hpp>
46 #include <rclcpp_action/rclcpp_action.hpp>
47 #include <tf2_msgs/action/lookup_transform.hpp>
48 
49 #include <stdexcept>
50 #include <string>
51 
52 namespace tf2_ros
53 {
57 class LookupTransformGoalException : public std::runtime_error
58 {
59 public:
61  explicit LookupTransformGoalException(const std::string & message)
62  : std::runtime_error(message)
63  {
64  }
65 };
66 
67 class GoalRejectedException : public LookupTransformGoalException
68 {
69 public:
71  explicit GoalRejectedException(const std::string & message)
73  {
74  }
75 };
76 
77 class GoalAbortedException : public LookupTransformGoalException
78 {
79 public:
81  explicit GoalAbortedException(const std::string & message)
83  {
84  }
85 };
86 
87 class GoalCanceledException : public LookupTransformGoalException
88 {
89 public:
91  explicit GoalCanceledException(const std::string & message)
93  {
94  }
95 };
96 
97 class UnexpectedResultCodeException : public LookupTransformGoalException
98 {
99 public:
101  explicit UnexpectedResultCodeException(const std::string & message)
103  {
104  }
105 };
106 
113 class BufferClient : public BufferInterface
114 {
115 public:
116  using LookupTransformAction = tf2_msgs::action::LookupTransform;
117 
124  template<typename NodePtr>
125  BufferClient(
126  NodePtr node,
127  const std::string ns,
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)
132  {
133  client_ = rclcpp_action::create_client<LookupTransformAction>(node, ns);
134  }
135 
136  virtual ~BufferClient() = default;
137 
161  geometry_msgs::msg::TransformStamped
163  const std::string & target_frame,
164  const std::string & source_frame,
165  const tf2::TimePoint & time,
166  const tf2::Duration timeout = tf2::durationFromSec(0.0)) const override;
167 
193  geometry_msgs::msg::TransformStamped
195  const std::string & target_frame,
196  const tf2::TimePoint & target_time,
197  const std::string & source_frame,
198  const tf2::TimePoint & source_time,
199  const std::string & fixed_frame,
200  const tf2::Duration timeout = tf2::durationFromSec(0.0)) const override;
201 
211  bool
212  canTransform(
213  const std::string & target_frame,
214  const std::string & source_frame,
215  const tf2::TimePoint & time,
216  const tf2::Duration timeout = tf2::durationFromSec(0.0),
217  std::string * errstr = nullptr) const override;
218 
230  bool
231  canTransform(
232  const std::string & target_frame,
233  const tf2::TimePoint & target_time,
234  const std::string & source_frame,
235  const tf2::TimePoint & source_time,
236  const std::string & fixed_frame,
237  const tf2::Duration timeout = tf2::durationFromSec(0.0),
238  std::string * errstr = nullptr) const override;
239 
245  bool waitForServer(const tf2::Duration & timeout = tf2::durationFromSec(0))
246  {
247  return client_->wait_for_action_server(timeout);
248  }
249 
250 private:
251  geometry_msgs::msg::TransformStamped
252  processGoal(const LookupTransformAction::Goal & goal) const;
253 
254  geometry_msgs::msg::TransformStamped
255  processResult(const LookupTransformAction::Result::SharedPtr & result) const;
256 
257  rclcpp_action::Client<LookupTransformAction>::SharedPtr client_;
258  double check_frequency_;
259  tf2::Duration timeout_padding_;
260 };
261 } // namespace tf2_ros
262 
263 #endif // TF2_ROS__BUFFER_CLIENT_H_
tf2_ros::LookupTransformGoalException
Definition: buffer_client.h:92
std::string
tf2_ros::BufferInterface
Abstract interface for wrapping tf2::BufferCoreInterface in a ROS-based API. Implementations include ...
Definition: buffer_interface.h:127
tf2_ros::BufferClient::lookupTransform
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout=tf2::durationFromSec(0.0)) const override
Get the transform between two frames by frame ID.
tf2_ros::BufferClient::LookupTransformAction
tf2_msgs::action::LookupTransform LookupTransformAction
Definition: buffer_client.h:151
tf2_ros::BufferClient::canTransform
TF2_ROS_PUBLIC bool canTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout=tf2::durationFromSec(0.0), std::string *errstr=nullptr) const override
Test if a transform is possible.
tf2_ros::UnexpectedResultCodeException::UnexpectedResultCodeException
TF2_ROS_PUBLIC UnexpectedResultCodeException(const std::string &message)
Definition: buffer_client.h:136
tf2_ros::LookupTransformGoalException::LookupTransformGoalException
TF2_ROS_PUBLIC LookupTransformGoalException(const std::string &message)
Definition: buffer_client.h:131
buffer_interface.h
tf2_ros
Definition: async_buffer_interface.h:43
tf2_ros::GoalRejectedException::GoalRejectedException
TF2_ROS_PUBLIC GoalRejectedException(const std::string &message)
Definition: buffer_client.h:106
std::runtime_error
tf2_ros::BufferClient::waitForServer
TF2_ROS_PUBLIC bool waitForServer(const tf2::Duration &timeout=tf2::durationFromSec(0))
Block until the action server is ready to respond to requests.
Definition: buffer_client.h:280
TF2_ROS_PUBLIC
#define TF2_ROS_PUBLIC
Definition: visibility_control.h:58
visibility_control.h
tf2_ros::BufferClient::BufferClient
BufferClient(NodePtr node, const std::string ns, const double &check_frequency=10.0, const tf2::Duration &timeout_padding=tf2::durationFromSec(2.0))
BufferClient constructor.
Definition: buffer_client.h:160
tf2_ros::GoalCanceledException::GoalCanceledException
TF2_ROS_PUBLIC GoalCanceledException(const std::string &message)
Definition: buffer_client.h:126
std
tf2_ros::BufferClient
Action client-based implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer_client.h:148
tf2_ros::GoalAbortedException::GoalAbortedException
TF2_ROS_PUBLIC GoalAbortedException(const std::string &message)
Definition: buffer_client.h:116
tf2_ros::BufferClient::~BufferClient
virtual ~BufferClient()=default