moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
transform_provider.cpp
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
38#include <tf2_ros/transform_listener.h>
39#include <tf2_ros/buffer.h>
40#include <tf2_eigen/tf2_eigen.hpp>
41
42TransformProvider::TransformProvider(double update_rate) : stop_(true), update_rate_(update_rate)
43{
44 tf_buffer_ = std::make_shared<tf2_ros::Buffer>();
45 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
46 psm_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description", tf_buffer_);
47 psm_->startStateMonitor();
48}
49
54
56{
57 stop_ = false;
58 thread_ = std::thread(&TransformProvider::run, this);
59}
60
62{
63 stop_ = true;
64 thread_.join();
65}
66
67void TransformProvider::addHandle(mesh_filter::MeshHandle handle, const std::string& name)
68{
69 if (!stop_)
70 throw std::runtime_error("Can not add handles if TransformProvider is running");
71
72 handle2context_[handle] = std::make_shared<TransformContext>(name);
73}
74
75void TransformProvider::setFrame(const std::string& frame)
76{
77 if (frame_id_ != frame)
78 {
79 frame_id_ = frame;
80 for (auto& context_it : handle2context_)
81 {
82 // invalidate transformations
83 context_it.second->mutex_.lock();
84 context_it.second->transformation_.matrix().setZero();
85 context_it.second->mutex_.unlock();
86 }
87 }
88}
89
90bool TransformProvider::getTransform(mesh_filter::MeshHandle handle, Eigen::Isometry3d& transform) const
91{
92 auto context_it = handle2context_.find(handle);
93
94 if (context_it == handle2context_.end())
95 {
96 ROS_ERROR("Unable to find mesh with handle %d", handle);
97 return false;
98 }
99 context_it->second->mutex_.lock();
100 transform = context_it->second->transformation_;
101 context_it->second->mutex_.unlock();
102 return !(transform.matrix().isZero(0));
103}
104
105void TransformProvider::run()
106{
107 if (handle2context_.empty())
108 throw std::runtime_error("TransformProvider is listening to empty list of frames!");
109
110 while (ros::ok() && !stop_)
111 {
112 updateTransforms();
113 update_rate_.sleep();
114 }
115}
116
117void TransformProvider::setUpdateRate(double update_rate)
118{
119 update_rate_ = ros::Rate(update_rate);
120}
121
122void TransformProvider::updateTransforms()
123{
124 // Don't bother if frame_id_ is empty (true initially)
125 if (frame_id_.empty())
126 {
127 ROS_DEBUG_THROTTLE(2., "Not updating transforms because frame_id_ is empty.");
128 return;
129 }
130
131 static tf2::Stamped<Eigen::Isometry3d> input_transform, output_transform;
132 static moveit::core::RobotStatePtr robot_state;
133 robot_state = psm_->getStateMonitor()->getCurrentState();
134 try
135 {
136 geometry_msgs::TransformStamped common_tf =
137 tf_buffer_->lookupTransform(frame_id_, psm_->getPlanningScene()->getPlanningFrame(), ros::Time(0.0));
138 input_transform.stamp_ = common_tf.header.stamp;
139 }
140 catch (tf2::TransformException& ex)
141 {
142 ROS_ERROR("TF Problem: %s", ex.what());
143 return;
144 }
145 input_transform.frame_id_ = psm_->getPlanningScene()->getPlanningFrame();
146
147 for (auto& context_it : handle2context_)
148 {
149 try
150 {
151 // TODO: check logic here - which global collision body's transform should be used?
152 input_transform.setData(robot_state->getGlobalLinkTransform(context_it.second->frame_id_));
153 tf_buffer_->transform(input_transform, output_transform, frame_id_);
154 }
155 catch (const tf2::TransformException& ex)
156 {
157 handle2context_[context_it.first]->mutex_.lock();
158 handle2context_[context_it.first]->transformation_.matrix().setZero();
159 handle2context_[context_it.first]->mutex_.unlock();
160 continue;
161 }
162 catch (std::exception& ex)
163 {
164 ROS_ERROR("Caught %s while updating transforms", ex.what());
165 }
166 handle2context_[context_it.first]->mutex_.lock();
167 handle2context_[context_it.first]->transformation_ = static_cast<Eigen::Isometry3d>(output_transform);
168 handle2context_[context_it.first]->mutex_.unlock();
169 }
170}
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