buffer.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #ifndef TF2_ROS_BUFFER_H
33 #define TF2_ROS_BUFFER_H
34 
36 #include <tf2/buffer_core.h>
37 #include <tf2_msgs/FrameGraph.h>
38 #include <ros/ros.h>
39 #include <tf2/convert.h>
40 
41 
42 namespace tf2_ros
43 {
44 
51  class Buffer: public BufferInterface, public tf2::BufferCore
52  {
53  public:
56 
63  Buffer(ros::Duration cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug = false);
64 
75  virtual geometry_msgs::TransformStamped
76  lookupTransform(const std::string& target_frame, const std::string& source_frame,
77  const ros::Time& time, const ros::Duration timeout) const;
78 
91  virtual geometry_msgs::TransformStamped
92  lookupTransform(const std::string& target_frame, const ros::Time& target_time,
93  const std::string& source_frame, const ros::Time& source_time,
94  const std::string& fixed_frame, const ros::Duration timeout) const;
95 
96 
105  virtual bool
106  canTransform(const std::string& target_frame, const std::string& source_frame,
107  const ros::Time& target_time, const ros::Duration timeout, std::string* errstr = NULL) const;
108 
119  virtual bool
120  canTransform(const std::string& target_frame, const ros::Time& target_time,
121  const std::string& source_frame, const ros::Time& source_time,
122  const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const;
123 
124 
125 
126 
127  private:
128  bool getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res) ;
129 
130 
131  // conditionally error if dedicated_thread unset.
132  bool checkAndErrorDedicatedThreadPresent(std::string* errstr) const;
133 
135 
136 
137  }; // class
138 
139 static const std::string threading_error = "Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a separate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance.";
140 
141 
142 } // namespace
143 
144 #endif // TF2_ROS_BUFFER_H
tf2_ros::BufferInterface
Abstract interface for wrapping tf2::BufferCore in a ROS-based API. Implementations include tf2_ros::...
Definition: buffer_interface.h:48
ros.h
tf2::BufferCore::lookupTransform
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame) const
tf2_ros::Buffer::frames_server_
ros::ServiceServer frames_server_
Definition: buffer.h:134
ros::ServiceServer
buffer_interface.h
tf2_ros
Definition: buffer.h:42
tf2_ros::threading_error
static const std::string threading_error
Definition: buffer.h:139
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
Get the transform between two frames by frame ID.
Definition: buffer.cpp:54
tf2_ros::Buffer::Buffer
Buffer(ros::Duration cache_time=ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug=false)
Constructor for a Buffer object.
Definition: buffer.cpp:43
tf2_ros::Buffer
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer.h:51
tf2::BufferCore::canTransform
bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
buffer_core.h
tf2_ros::Buffer::getFrames
bool getFrames(tf2_msgs::FrameGraph::Request &req, tf2_msgs::FrameGraph::Response &res)
Definition: buffer.cpp:177
ros::Time
tf2::BufferCore
convert.h
tf2_ros::Buffer::checkAndErrorDedicatedThreadPresent
bool checkAndErrorDedicatedThreadPresent(std::string *errstr) const
Definition: buffer.cpp:185
ros::Duration
tf2_ros::Buffer::canTransform
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
Test if a transform is possible.
Definition: buffer.cpp:119


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:16