53 state_monitors_.clear();
55 robot_model_loaders_.clear();
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_;
65SharedStorage& getSharedStorage()
70 static SharedStorage storage;
73 static SharedStorage* storage =
new SharedStorage;
85 SharedStorage& s = getSharedStorage();
86 std::scoped_lock slock(s.lock_);
88 std::shared_ptr<tf2_ros::Buffer> buffer = s.tf_buffer_.lock();
91 buffer = std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>(RCL_ROS_TIME));
92 s.tf_buffer_ = buffer;
98 const std::string& robot_description)
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()))
106 auto rml = it->second.lock();
109 rml = std::make_shared<RobotModelLoader>(node, robot_description);
116 const std::string& robot_description)
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();
126 model = moveit::core::RobotModelPtr(loader, loader->getModel().get());
133 const moveit::core::RobotModelConstPtr& robot_model,
134 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
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();
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;
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.
This namespace includes the base class for MoveIt planners.