55 state_monitors_.clear();
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_;
65 SharedStorage& getSharedStorage()
67 #if 0 // destruction of static storage interferes with static destruction in class_loader
70 static SharedStorage storage;
72 #else // thus avoid destruction at all (until class_loader is fixed)
73 static SharedStorage* storage =
new SharedStorage;
79 template <
typename T,
typename O>
83 CoupledDeleter(
const O* other =
nullptr) : other_(other)
87 void operator()(
const T* p)
101 SharedStorage&
s = getSharedStorage();
102 boost::mutex::scoped_lock slock(
s.lock_);
104 typedef CoupledDeleter<tf2_ros::Buffer, tf2_ros::TransformListener> Deleter;
105 std::shared_ptr<tf2_ros::Buffer> buffer =
s.tf_buffer_.lock();
111 s.tf_buffer_ = buffer;
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();
124 RobotModelLoader::Options opt(robot_description);
125 opt.load_kinematics_solvers_ =
true;
128 model = moveit::core::RobotModelPtr(loader, loader->getModel().get());
135 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
141 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
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();
151 monitor = std::make_shared<CurrentStateMonitor>(robot_model,
tf_buffer, nh);
152 it->second = monitor;