moveit2
The MoveIt Motion Planning Framework for ROS 2.
transform_provider.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Suat Gedikli */
36 
37 #pragma once
38 
39 #include <string>
43 #include <map>
44 
45 namespace tf2_ros
46 {
47 class TransformListener;
48 class Buffer;
49 } // namespace tf2_ros
50 
56 {
57 public:
63  TransformProvider(double update_rate = 30.);
64 
67 
75  bool getTransform(mesh_filter::MeshHandle handle, Eigen::Isometry3d& transform) const;
76 
83  void addHandle(mesh_filter::MeshHandle handle, const std::string& name);
84 
90  void setFrame(const std::string& frame);
91 
96  void start();
97 
102  void stop();
103 
110  void setUpdateRate(double update_rate);
111 
112 private:
118  void updateTransforms();
119 
120  MOVEIT_CLASS_FORWARD(TransformContext); // Defines TransformContextPtr, ConstPtr, WeakPtr... etc
121 
126  class TransformContext
127  {
128  public:
129  TransformContext(const std::string& name) : frame_id_(name)
130  {
131  transformation_.matrix().setZero();
132  }
134  std::string frame_id_;
135  Eigen::Isometry3d transformation_;
136  std::mutex mutex_;
137  };
138 
143  void run();
144 
146  std::map<mesh_filter::MeshHandle, TransformContextPtr> handle2context_;
147 
149  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
150  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
151 
153  planning_scene_monitor::PlanningSceneMonitorPtr psm_;
154 
156  std::string frame_id_;
157 
159  std::thread thread_;
160 
162  bool stop_;
163 
165  ros::Rate update_rate_;
166 };
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
Class that caches and updates transformations for given frames.
void start()
starts the updating process. Done in a separate thread
void stop()
stops the update process/thread.
void setFrame(const std::string &frame)
sets the camera frame id. The returned transformations are in respect to this coordinate frame
void addHandle(mesh_filter::MeshHandle handle, const std::string &name)
registers a mesh with its handle
~TransformProvider()
Destructor.
void setUpdateRate(double update_rate)
sets the update rate in Hz. This should be slow enough to reduce the system load but fast enough to g...
TransformProvider(double update_rate=30.)
Constructor.
bool getTransform(mesh_filter::MeshHandle handle, Eigen::Isometry3d &transform) const
returns the current transformation of a mesh given by its handle
unsigned int MeshHandle
name
Definition: setup.py:7
std::mutex mutex_