moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
38 
39 using namespace planning_scene_monitor;
40 using namespace robot_model_loader;
41 
42 namespace
43 {
44 struct SharedStorage
45 {
46  SharedStorage()
47  {
48  }
49 
50  ~SharedStorage()
51  {
52  tf_buffer_.reset();
53  state_monitors_.clear();
54  models_.clear();
55  robot_model_loaders_.clear();
56  }
57 
58  std::recursive_mutex lock_;
59  std::weak_ptr<tf2_ros::Buffer> tf_buffer_;
60  std::map<std::string, moveit::core::RobotModelWeakPtr> models_;
61  std::map<std::string, CurrentStateMonitorWeakPtr> state_monitors_;
62  std::map<std::string, RobotModelLoaderWeakPtr> robot_model_loaders_;
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 } // namespace
78 
79 namespace moveit
80 {
81 namespace planning_interface
82 {
83 std::shared_ptr<tf2_ros::Buffer> getSharedTF()
84 {
85  SharedStorage& s = getSharedStorage();
86  std::scoped_lock slock(s.lock_);
87 
88  std::shared_ptr<tf2_ros::Buffer> buffer = s.tf_buffer_.lock();
89  if (!buffer)
90  {
91  buffer = std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>(RCL_ROS_TIME));
92  s.tf_buffer_ = buffer;
93  }
94  return buffer;
95 }
96 
97 robot_model_loader::RobotModelLoaderPtr getSharedRobotModelLoader(const rclcpp::Node::SharedPtr& node,
98  const std::string& robot_description)
99 {
100  SharedStorage& s = getSharedStorage();
101  std::scoped_lock slock(s.lock_);
102  auto it = s.robot_model_loaders_
103  .insert(std::make_pair(node->get_fully_qualified_name() + robot_description,
104  robot_model_loader::RobotModelLoaderWeakPtr()))
105  .first;
106  auto rml = it->second.lock();
107  if (!rml)
108  {
109  rml = std::make_shared<RobotModelLoader>(node, robot_description);
110  it->second = rml;
111  }
112  return rml;
113 }
114 
115 moveit::core::RobotModelConstPtr getSharedRobotModel(const rclcpp::Node::SharedPtr& node,
116  const std::string& robot_description)
117 {
118  SharedStorage& s = getSharedStorage();
119  std::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  RobotModelLoaderPtr loader = getSharedRobotModelLoader(node, robot_description);
125  // create an aliasing shared_ptr
126  model = moveit::core::RobotModelPtr(loader, loader->getModel().get());
127  it->second = model;
128  }
129  return model;
130 }
131 
132 CurrentStateMonitorPtr getSharedStateMonitor(const rclcpp::Node::SharedPtr& node,
133  const moveit::core::RobotModelConstPtr& robot_model,
134  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
135 {
136  SharedStorage& s = getSharedStorage();
137  std::scoped_lock slock(s.lock_);
138  auto it = s.state_monitors_.insert(std::make_pair(robot_model->getName(), CurrentStateMonitorWeakPtr())).first;
139  CurrentStateMonitorPtr monitor = it->second.lock();
140  if (!monitor)
141  {
142  // if there was no valid entry, create one
143  const bool use_sim_time = node->get_parameter("use_sim_time").as_bool();
144  monitor = std::make_shared<CurrentStateMonitor>(node, robot_model, tf_buffer, use_sim_time);
145  it->second = monitor;
146  }
147  return monitor;
148 }
149 } // namespace planning_interface
150 } // namespace moveit
moveit::core::RobotModelConstPtr getSharedRobotModel(const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
std::shared_ptr< tf2_ros::Buffer > getSharedTF()
robot_model_loader::RobotModelLoaderPtr getSharedRobotModelLoader(const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
getSharedStateMonitor
Main namespace for MoveIt.
Definition: exceptions.h:43
This namespace includes the base class for MoveIt planners.