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 #ifndef TF2_ROS_BUFFER_CLIENT_H_
38 #define TF2_ROS_BUFFER_CLIENT_H_
39 
42 #include <tf2_msgs/LookupTransformAction.h>
43 
44 namespace tf2_ros
45 {
53  {
54  public:
56 
62  BufferClient(std::string ns, double check_frequency = 10.0, ros::Duration timeout_padding = ros::Duration(2.0));
63 
74  virtual geometry_msgs::TransformStamped
75  lookupTransform(const std::string& target_frame, const std::string& source_frame,
76  const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0)) const;
77 
90  virtual geometry_msgs::TransformStamped
91  lookupTransform(const std::string& target_frame, const ros::Time& target_time,
92  const std::string& source_frame, const ros::Time& source_time,
93  const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0)) const;
94 
103  virtual bool
104  canTransform(const std::string& target_frame, const std::string& source_frame,
105  const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const;
106 
117  virtual bool
118  canTransform(const std::string& target_frame, const ros::Time& target_time,
119  const std::string& source_frame, const ros::Time& source_time,
120  const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const;
121 
126  bool waitForServer(const ros::Duration& timeout = ros::Duration(0))
127  {
128  return client_.waitForServer(timeout);
129  }
130 
131  private:
132  geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal& goal) const;
133  geometry_msgs::TransformStamped processResult(const tf2_msgs::LookupTransformResult& result) const;
134  mutable LookupActionClient client_;
137  };
138 };
139 #endif
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
actionlib::SimpleActionClient< tf2_msgs::LookupTransformAction > LookupActionClient
Definition: buffer_client.h:55
Abstract interface for wrapping tf2::BufferCore in a ROS-based API. Implementations include tf2_ros::...
bool waitForServer(const ros::Duration &timeout=ros::Duration(0))
Block until the action server is ready to respond to requests.
ros::Duration timeout_padding_
LookupActionClient client_
geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal &goal) const
Definition: buffer.h:42
BufferClient(std::string ns, double check_frequency=10.0, ros::Duration timeout_padding=ros::Duration(2.0))
BufferClient constructor.
Action client-based implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer_client.h:52
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.


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Oct 16 2020 19:08:54