common_objects.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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: Ioan Sucan */
36 
40 
41 using namespace planning_scene_monitor;
42 using namespace robot_model_loader;
43 
44 namespace
45 {
46 struct SharedStorage
47 {
48  SharedStorage()
49  {
50  }
51 
52  ~SharedStorage()
53  {
54  tf_buffer_.reset();
55  state_monitors_.clear();
56  models_.clear();
57  }
58 
59  boost::mutex lock_;
60  std::weak_ptr<tf2_ros::Buffer> tf_buffer_;
61  std::map<std::string, moveit::core::RobotModelWeakPtr> models_;
62  std::map<std::string, CurrentStateMonitorWeakPtr> state_monitors_;
63 };
64 
65 SharedStorage& getSharedStorage()
66 {
67 #if 0 // destruction of static storage interferes with static destruction in class_loader
68  // More specifically, class_loader's static variables might be already destroyed
69  // while being accessed again in the destructor of the class_loader-based kinematics plugin.
70  static SharedStorage storage;
71  return storage;
72 #else // thus avoid destruction at all (until class_loader is fixed)
73  static SharedStorage* storage = new SharedStorage;
74  return *storage;
75 #endif
76 }
77 
78 // Deleter that, additionally to T*, deletes another object too
79 template <typename T, typename O>
80 struct CoupledDeleter
81 {
82  const O* other_;
83  CoupledDeleter(const O* other = nullptr) : other_(other)
84  {
85  }
86 
87  void operator()(const T* p)
88  {
89  delete other_;
90  delete p;
91  }
92 };
93 } // namespace
94 
95 namespace moveit
96 {
97 namespace planning_interface
98 {
99 std::shared_ptr<tf2_ros::Buffer> getSharedTF()
100 {
101  SharedStorage& s = getSharedStorage();
102  boost::mutex::scoped_lock slock(s.lock_);
103 
104  typedef CoupledDeleter<tf2_ros::Buffer, tf2_ros::TransformListener> Deleter;
105  std::shared_ptr<tf2_ros::Buffer> buffer = s.tf_buffer_.lock();
106  if (!buffer)
107  {
108  tf2_ros::Buffer* raw = new tf2_ros::Buffer();
109  // assign custom deleter to also delete associated TransformListener
110  buffer.reset(raw, Deleter(new tf2_ros::TransformListener(*raw)));
111  s.tf_buffer_ = buffer;
112  }
113  return buffer;
114 }
115 
116 moveit::core::RobotModelConstPtr getSharedRobotModel(const std::string& robot_description)
117 {
118  SharedStorage& s = getSharedStorage();
119  boost::mutex::scoped_lock slock(s.lock_);
120  auto it = s.models_.insert(std::make_pair(robot_description, moveit::core::RobotModelWeakPtr())).first;
121  moveit::core::RobotModelPtr model = it->second.lock();
122  if (!model)
123  {
124  RobotModelLoader::Options opt(robot_description);
125  opt.load_kinematics_solvers_ = true;
126  RobotModelLoaderPtr loader(new RobotModelLoader(opt));
127  // create an aliasing shared_ptr
128  model = moveit::core::RobotModelPtr(loader, loader->getModel().get());
129  it->second = model;
130  }
131  return model;
132 }
133 
134 CurrentStateMonitorPtr getSharedStateMonitor(const moveit::core::RobotModelConstPtr& robot_model,
135  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
136 {
137  return getSharedStateMonitor(robot_model, tf_buffer, ros::NodeHandle());
138 }
139 
140 CurrentStateMonitorPtr getSharedStateMonitor(const moveit::core::RobotModelConstPtr& robot_model,
141  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
142  const ros::NodeHandle& nh)
143 {
144  SharedStorage& s = getSharedStorage();
145  boost::mutex::scoped_lock slock(s.lock_);
146  auto it = s.state_monitors_.insert(std::make_pair(robot_model->getName(), CurrentStateMonitorWeakPtr())).first;
147  CurrentStateMonitorPtr monitor = it->second.lock();
148  if (!monitor)
149  {
150  // if there was no valid entry, create one
151  monitor = std::make_shared<CurrentStateMonitor>(robot_model, tf_buffer, nh);
152  it->second = monitor;
153  }
154  return monitor;
155 }
156 
157 } // namespace planning_interface
158 } // namespace moveit
planning_scene_monitor
s
XmlRpcServer s
robot_model_loader
robot_model_loader::RobotModelLoader
robot_model_loader.h
moveit::planning_interface::getSharedTF
std::shared_ptr< tf2_ros::Buffer > getSharedTF()
Definition: common_objects.cpp:99
tf2_ros::TransformListener
tf2_ros::Buffer
common_objects.h
transform_listener.h
moveit::planning_interface::getSharedStateMonitor
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor(const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
getSharedStateMonitor is a simpler version of getSharedStateMonitor(const moveit::core::RobotModelCon...
Definition: common_objects.cpp:134
moveit
tf_buffer
tf2_ros::Buffer * tf_buffer
moveit::planning_interface::getSharedRobotModel
moveit::core::RobotModelConstPtr getSharedRobotModel(const std::string &robot_description)
Definition: common_objects.cpp:116
planning_interface
ros::NodeHandle


planning_interface
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:25:17