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 
39 #include <tf2_ros/buffer.h>
40 #include <tf2_eigen/tf2_eigen.h>
41 
42 TransformProvider::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 
51 {
52  stop();
53 }
54 
56 {
57  stop_ = false;
58  thread_ = std::thread(&TransformProvider::run, this);
59 }
60 
62 {
63  stop_ = true;
64  thread_.join();
65 }
66 
67 void 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 
75 void 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 
90 bool 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 
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  {
114  }
115 }
116 
117 void TransformProvider::setUpdateRate(double update_rate)
118 {
119  update_rate_ = ros::Rate(update_rate);
120 }
121 
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 }
TransformProvider::TransformProvider
TransformProvider(double update_rate=30.)
Constructor.
Definition: transform_provider.cpp:42
TransformProvider::updateTransforms
void updateTransforms()
this method is called periodically by the dedicated thread and updates all the transformations of the...
Definition: transform_provider.cpp:122
TransformProvider::setFrame
void setFrame(const std::string &frame)
sets the camera frame id. The returned transformations are in respect to this coordinate frame
Definition: transform_provider.cpp:75
TransformProvider::~TransformProvider
~TransformProvider()
Destructor.
Definition: transform_provider.cpp:50
tf2::Stamped::setData
void setData(const T &input)
tf2_eigen.h
TransformProvider::setUpdateRate
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...
Definition: transform_provider.cpp:117
buffer.h
tf2::Stamped
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
TransformProvider::update_rate_
ros::Rate update_rate_
update rate in Hz
Definition: transform_provider.h:165
ros::ok
ROSCPP_DECL bool ok()
TransformProvider::addHandle
void addHandle(mesh_filter::MeshHandle handle, const std::string &name)
registers a mesh with its handle
Definition: transform_provider.cpp:67
TransformProvider::tf_buffer_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: transform_provider.h:150
TransformProvider::psm_
planning_scene_monitor::PlanningSceneMonitorPtr psm_
SceneMonitor used to get current states.
Definition: transform_provider.h:153
TransformProvider::frame_id_
std::string frame_id_
the camera frame id
Definition: transform_provider.h:156
name
std::string name
tf2::Stamped::frame_id_
std::string frame_id_
ROS_ERROR
#define ROS_ERROR(...)
TransformProvider::stop_
bool stop_
Definition: transform_provider.h:162
tf2::Stamped::stamp_
ros::Time stamp_
ros::Rate::sleep
bool sleep()
TransformProvider::tf_listener_
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
TransformListener used to listen and update transformations.
Definition: transform_provider.h:149
transform_provider.h
transform_listener.h
mesh_filter::MeshHandle
unsigned int MeshHandle
Definition: mesh_filter_base.h:60
ros::Time
TransformProvider::getTransform
bool getTransform(mesh_filter::MeshHandle handle, Eigen::Isometry3d &transform) const
returns the current transformation of a mesh given by its handle
Definition: transform_provider.cpp:90
ros::Rate
TransformProvider::run
void run()
The entry point of the dedicated thread that updates the transformations periodically.
Definition: transform_provider.cpp:105
TransformProvider::stop
void stop()
stops the update process/thread.
Definition: transform_provider.cpp:61
tf2::TransformException
TransformProvider::start
void start()
starts the updating process. Done in a seperate thread
Definition: transform_provider.cpp:55
TransformProvider::thread_
std::thread thread_
thread object
Definition: transform_provider.h:159
ROS_DEBUG_THROTTLE
#define ROS_DEBUG_THROTTLE(period,...)
TransformProvider::handle2context_
std::map< mesh_filter::MeshHandle, TransformContextPtr > handle2context_
mapping between the mesh handle and its context
Definition: transform_provider.h:146


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Thu Jun 27 2024 02:27:09