moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_scene_monitor.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, 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
41#include <moveit_msgs/srv/get_planning_scene.hpp>
43
44#include <tf2/exceptions.h>
45#include <tf2/LinearMath/Transform.h>
46#include <tf2_eigen/tf2_eigen.hpp>
47#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
48
49#include <fmt/format.h>
50#include <memory>
51
52#include <std_msgs/msg/string.hpp>
53
54#include <chrono>
55using namespace std::chrono_literals;
56
58{
59const std::string PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC = "joint_states";
60const std::string PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC = "attached_collision_object";
61const std::string PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC = "collision_object";
62const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC = "planning_scene_world";
63const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC = "planning_scene";
64const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_SERVICE = "get_planning_scene";
65const std::string PlanningSceneMonitor::MONITORED_PLANNING_SCENE_TOPIC = "monitored_planning_scene";
66
67PlanningSceneMonitor::PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const std::string& robot_description,
68 const std::string& name)
69 : PlanningSceneMonitor(node, planning_scene::PlanningScenePtr(), robot_description, name)
70{
71}
72
73PlanningSceneMonitor::PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node,
74 const planning_scene::PlanningScenePtr& scene,
75 const std::string& robot_description, const std::string& name)
76 : PlanningSceneMonitor(node, scene, std::make_shared<robot_model_loader::RobotModelLoader>(node, robot_description),
77 name)
78{
79}
80
81PlanningSceneMonitor::PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node,
82 const robot_model_loader::RobotModelLoaderPtr& rm_loader,
83 const std::string& name)
84 : PlanningSceneMonitor(node, planning_scene::PlanningScenePtr(), rm_loader, name)
85{
86}
87
88PlanningSceneMonitor::PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node,
89 const planning_scene::PlanningScenePtr& scene,
90 const robot_model_loader::RobotModelLoaderPtr& rm_loader,
91 const std::string& name)
92 : monitor_name_(name)
93 , node_(node)
94 , private_executor_(std::make_shared<rclcpp::executors::SingleThreadedExecutor>())
95 , tf_buffer_(std::make_shared<tf2_ros::Buffer>(node->get_clock()))
96 , dt_state_update_(0.0)
97 , shape_transform_cache_lookup_wait_time_(0, 0)
98 , rm_loader_(rm_loader)
99 , logger_(moveit::getLogger("moveit.ros.planning_scene_monitor"))
100{
101 std::vector<std::string> new_args = rclcpp::NodeOptions().arguments();
102 new_args.push_back("--ros-args");
103 new_args.push_back("-r");
104 // Add random ID to prevent warnings about multiple publishers within the same node
105 new_args.push_back(std::string("__node:=") + node_->get_name() + "_private_" +
106 std::to_string(reinterpret_cast<std::size_t>(this)));
107 new_args.push_back("--");
108 pnode_ = std::make_shared<rclcpp::Node>("_", node_->get_namespace(), rclcpp::NodeOptions().arguments(new_args));
109 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
110 tf_buffer_->setUsingDedicatedThread(true);
111 // use same callback queue as root_nh_
112 // root_nh_.setCallbackQueue(&queue_);
113 // nh_.setCallbackQueue(&queue_);
114 // spinner_.reset(new ros::AsyncSpinner(1, &queue_));
115 // spinner_->start();
116 initialize(scene);
117
118 use_sim_time_ = node->get_parameter("use_sim_time").as_bool();
119}
120
122{
123 if (scene_)
124 {
125 scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
126 scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
127 }
132
133 private_executor_->cancel();
134 if (private_executor_thread_.joinable())
136 private_executor_.reset();
137
139 scene_const_.reset();
140 scene_.reset();
141 parent_scene_.reset();
142 robot_model_.reset();
143 rm_loader_.reset();
144}
145
146void PlanningSceneMonitor::initialize(const planning_scene::PlanningScenePtr& scene)
147{
148 if (monitor_name_.empty())
149 monitor_name_ = "planning_scene_monitor";
150 robot_description_ = rm_loader_->getRobotDescription();
151 if (rm_loader_->getModel())
152 {
153 robot_model_ = rm_loader_->getModel();
154 scene_ = scene;
155 if (!scene_)
156 {
157 try
158 {
159 scene_ = std::make_shared<planning_scene::PlanningScene>(rm_loader_->getModel());
162
163 scene_->getCollisionEnvNonConst()->setPadding(default_robot_padd_);
164 scene_->getCollisionEnvNonConst()->setScale(default_robot_scale_);
165 for (const std::pair<const std::string, double>& it : default_robot_link_padd_)
166 {
167 scene_->getCollisionEnvNonConst()->setLinkPadding(it.first, it.second);
168 }
169 for (const std::pair<const std::string, double>& it : default_robot_link_scale_)
170 {
171 scene_->getCollisionEnvNonConst()->setLinkScale(it.first, it.second);
172 }
173 }
175 {
176 RCLCPP_ERROR(logger_, "Configuration of planning scene failed");
177 scene_.reset();
178 }
179 }
180 // scene_const_ is set regardless if scene_ is null or not
182 if (scene_)
183 {
184 // The scene_ is loaded on the collision loader only if it was correctly instantiated
185 collision_loader_.setupScene(node_, scene_);
186 scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
188 });
189 scene_->setCollisionObjectUpdateCallback(
190 [this](const collision_detection::World::ObjectConstPtr& object, collision_detection::World::Action action) {
191 currentWorldObjectUpdateCallback(object, action);
192 });
193 }
194 }
195 else
196 {
197 RCLCPP_ERROR(logger_, "Robot model not loaded");
198 }
199
202
203 last_update_time_ = last_robot_motion_time_ = rclcpp::Clock().now();
204 last_robot_state_update_wall_time_ = std::chrono::system_clock::now();
205 dt_state_update_ = std::chrono::duration<double>(0.03);
206
207 double temp_wait_time = 0.05;
208
209 if (!robot_description_.empty())
210 {
211 node_->get_parameter_or(robot_description_ + "_planning.shape_transform_cache_lookup_wait_time", temp_wait_time,
212 temp_wait_time);
213 }
214
215 shape_transform_cache_lookup_wait_time_ = rclcpp::Duration::from_seconds(temp_wait_time);
216
217 state_update_pending_ = false;
218 // Period for 0.1 sec
219 using std::chrono::nanoseconds;
220 state_update_timer_ = pnode_->create_wall_timer(dt_state_update_, [this]() { return stateUpdateTimerCallback(); });
221 private_executor_->add_node(pnode_);
222
223 // start executor on a different thread now
224 private_executor_thread_ = std::thread([this]() { private_executor_->spin(); });
225
226 auto declare_parameter = [this](const std::string& param_name, auto default_val,
227 const std::string& description) -> auto
228 {
229 rcl_interfaces::msg::ParameterDescriptor desc;
230 desc.set__description(description);
231 return pnode_->declare_parameter(param_name, default_val, desc);
232 };
233
234 try
235 {
236 bool publish_planning_scene = false;
237 bool publish_geometry_updates = false;
238 bool publish_state_updates = false;
239 bool publish_transform_updates = false;
240 double publish_planning_scene_hz = 4.0;
241 if (node_->has_parameter("publish_planning_scene"))
242 {
243 publish_planning_scene = node_->get_parameter("publish_planning_scene").as_bool();
244 }
245 if (node_->has_parameter("publish_geometry_updates"))
246 {
247 publish_geometry_updates = node_->get_parameter("publish_geometry_updates").as_bool();
248 }
249 if (node_->has_parameter("publish_state_updates"))
250 {
251 publish_state_updates = node_->get_parameter("publish_state_updates").as_bool();
252 }
253 if (node_->has_parameter("publish_transforms_updates"))
254 {
255 publish_transform_updates = node_->get_parameter("publish_transforms_updates").as_bool();
256 }
257 if (node_->has_parameter("publish_planning_scene_hz"))
258 {
259 publish_planning_scene_hz = node_->get_parameter("publish_planning_scene_hz").as_double();
260 }
261
262 // Set up publishing parameters
263 publish_planning_scene =
264 declare_parameter("publish_planning_scene", publish_planning_scene, "Set to True to publish Planning Scenes");
265 publish_geometry_updates = declare_parameter("publish_geometry_updates", publish_geometry_updates,
266 "Set to True to publish geometry updates of the planning scene");
267 publish_state_updates = declare_parameter("publish_state_updates", publish_state_updates,
268 "Set to True to publish state updates of the planning scene");
269 publish_transform_updates = declare_parameter("publish_transforms_updates", publish_transform_updates,
270 "Set to True to publish transform updates of the planning scene");
271 publish_planning_scene_hz =
272 declare_parameter("publish_planning_scene_hz", publish_planning_scene_hz,
273 "Set the maximum frequency at which planning scene updates are published");
274 updatePublishSettings(publish_geometry_updates, publish_state_updates, publish_transform_updates,
275 publish_planning_scene, publish_planning_scene_hz);
276 }
277 catch (const rclcpp::exceptions::InvalidParameterTypeException& e)
278 {
279 RCLCPP_ERROR_STREAM(logger_, "Invalid parameter type in PlanningSceneMonitor: " << e.what());
280 RCLCPP_ERROR(logger_, "Dynamic publishing parameters won't be available");
281 return;
282 }
283
284 auto psm_parameter_set_callback = [this](const std::vector<rclcpp::Parameter>& parameters) -> auto
285 {
286 auto result = rcl_interfaces::msg::SetParametersResult();
287 result.successful = true;
288
289 bool publish_planning_scene = false, publish_geometry_updates = false, publish_state_updates = false,
290 publish_transform_updates = false;
291 double publish_planning_scene_hz = 4.0;
292 bool declared_params_valid = pnode_->get_parameter("publish_planning_scene", publish_planning_scene) &&
293 pnode_->get_parameter("publish_geometry_updates", publish_geometry_updates) &&
294 pnode_->get_parameter("publish_state_updates", publish_state_updates) &&
295 pnode_->get_parameter("publish_transforms_updates", publish_transform_updates) &&
296 pnode_->get_parameter("publish_planning_scene_hz", publish_planning_scene_hz);
297
298 if (!declared_params_valid)
299 {
300 RCLCPP_ERROR(logger_, "Initially declared parameters are invalid - failed to process update callback");
301 result.successful = false;
302 return result;
303 }
304
305 for (const auto& parameter : parameters)
306 {
307 const auto& name = parameter.get_name();
308 const auto& type = parameter.get_type();
309
310 // Only allow already declared parameters with same value type
311 if (!pnode_->has_parameter(name) || pnode_->get_parameter(name).get_type() != type)
312 {
313 RCLCPP_ERROR(logger_, "Invalid parameter in PlanningSceneMonitor parameter callback");
314 result.successful = false;
315 return result;
316 }
317
318 // Update parameter values
319 if (name == "planning_scene_monitor.publish_planning_scene")
320 {
321 publish_planning_scene = parameter.as_bool();
322 }
323 else if (name == "planning_scene_monitor.publish_geometry_updates")
324 {
325 publish_geometry_updates = parameter.as_bool();
326 }
327 else if (name == "planning_scene_monitor.publish_state_updates")
328 {
329 publish_state_updates = parameter.as_bool();
330 }
331 else if (name == "planning_scene_monitor.publish_transforms_updates")
332 {
333 publish_transform_updates = parameter.as_bool();
334 }
335 else if (name == "planning_scene_monitor.publish_planning_scene_hz")
336 {
337 publish_planning_scene_hz = parameter.as_double();
338 }
339 }
340
341 if (result.successful)
342 {
343 updatePublishSettings(publish_geometry_updates, publish_state_updates, publish_transform_updates,
344 publish_planning_scene, publish_planning_scene_hz);
345 }
346 return result;
347 };
348
349 callback_handler_ = pnode_->add_on_set_parameters_callback(psm_parameter_set_callback);
350}
351
353{
354 if (scene_)
355 {
356 if (flag)
357 {
358 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
359 if (scene_)
360 {
361 scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
362 scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
363 scene_->decoupleParent();
365 scene_ = parent_scene_->diff();
367 scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
369 });
370 scene_->setCollisionObjectUpdateCallback(
371 [this](const collision_detection::World::ObjectConstPtr& object,
373 }
374 }
375 else
376 {
378 {
379 RCLCPP_WARN(logger_, "Diff monitoring was stopped while publishing planning scene diffs. "
380 "Stopping planning scene diff publisher");
382 }
383 {
384 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
385 if (scene_)
386 {
387 scene_->decoupleParent();
388 parent_scene_.reset();
389 // remove the '+' added by .diff() at the end of the scene name
390 if (!scene_->getName().empty())
391 {
392 if (scene_->getName()[scene_->getName().length() - 1] == '+')
393 scene_->setName(scene_->getName().substr(0, scene_->getName().length() - 1));
394 }
395 }
396 }
397 }
398 }
399}
400
402{
404 {
405 std::unique_ptr<std::thread> copy;
406 copy.swap(publish_planning_scene_);
407 new_scene_update_condition_.notify_all();
408 copy->join();
409 monitorDiffs(false);
411 RCLCPP_INFO(logger_, "Stopped publishing maintained planning scene.");
412 }
413}
414
416 const std::string& planning_scene_topic)
417{
418 publish_update_types_ = update_type;
419
421 {
422 RCLCPP_INFO(logger_, "Stopping existing planning scene publisher.");
424 }
425
426 if (scene_)
427 {
428 planning_scene_publisher_ = pnode_->create_publisher<moveit_msgs::msg::PlanningScene>(planning_scene_topic, 100);
429 RCLCPP_INFO(logger_, "Publishing maintained planning scene on '%s'", planning_scene_topic.c_str());
430 monitorDiffs(true);
431 publish_planning_scene_ = std::make_unique<std::thread>([this] { scenePublishingThread(); });
432 }
433 else
434 {
435 RCLCPP_WARN(logger_, "Did not find a planning scene, so cannot publish it.");
436 }
437}
438
439void PlanningSceneMonitor::scenePublishingThread()
440{
441 RCLCPP_DEBUG(logger_, "Started scene publishing thread ...");
442
443 // publish the full planning scene once
444 {
445 moveit_msgs::msg::PlanningScene msg;
446 {
449 lock = octomap_monitor_->getOcTreePtr()->reading();
450 scene_->getPlanningSceneMsg(msg);
451 }
452 planning_scene_publisher_->publish(msg);
453 RCLCPP_DEBUG(logger_, "Published the full planning scene: '%s'", msg.name.c_str());
454 }
455
456 do
457 {
458 moveit_msgs::msg::PlanningScene msg;
459 bool publish_msg = false;
460 bool is_full = false;
461 rclcpp::Rate rate(publish_planning_scene_frequency_);
462 {
463 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
465 new_scene_update_condition_.wait(ulock);
467 {
469 {
471 {
472 is_full = true;
473 }
474 else
475 {
478 lock = octomap_monitor_->getOcTreePtr()->reading();
479 scene_->getPlanningSceneDiffMsg(msg);
481 {
482 msg.robot_state.attached_collision_objects.clear();
483 msg.robot_state.is_diff = true;
484 }
485 }
486 std::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the
487 // transform cache to
488 // update while we are
489 // potentially changing
490 // attached bodies
491 scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
492 scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
493 scene_->pushDiffs(parent_scene_);
494 scene_->clearDiffs();
495 scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
497 });
498 scene_->setCollisionObjectUpdateCallback(
499 [this](const collision_detection::World::ObjectConstPtr& object,
502 {
503 excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
504 excludeWorldObjectsFromOctree(); // in case updates have happened to the attached bodies, put them in
505 }
506 if (is_full)
507 {
510 lock = octomap_monitor_->getOcTreePtr()->reading();
511 scene_->getPlanningSceneMsg(msg);
512 }
513 // also publish timestamp of this robot_state
514 msg.robot_state.joint_state.header.stamp = last_robot_motion_time_;
515 publish_msg = true;
516 }
518 }
519 }
520 if (publish_msg)
521 {
522 planning_scene_publisher_->publish(msg);
523 if (is_full)
524 RCLCPP_DEBUG(logger_, "Published full planning scene: '%s'", msg.name.c_str());
525 rate.sleep();
526 }
527 } while (publish_planning_scene_);
528}
529
530void PlanningSceneMonitor::getMonitoredTopics(std::vector<std::string>& topics) const
531{
532 // TODO(anasarrak): Do we need this for ROS2?
533 topics.clear();
535 {
536 const std::string& t = current_state_monitor_->getMonitoredTopic();
537 if (!t.empty())
538 topics.push_back(t);
539 }
541 topics.push_back(planning_scene_subscriber_->get_topic_name());
543 {
544 // TODO (anasarrak) This has been changed to subscriber on Moveit, look at
545 // https://github.com/moveit/moveit/pull/1406/files/cb9488312c00e9c8949d89b363766f092330954d#diff-fb6e26ecc9a73d59dbdae3f3e08145e6
546 topics.push_back(collision_object_subscriber_->get_topic_name());
547 }
549 topics.push_back(planning_scene_world_subscriber_->get_topic_name());
550}
551
552namespace
553{
554bool sceneIsParentOf(const planning_scene::PlanningSceneConstPtr& scene,
555 const planning_scene::PlanningScene* possible_parent)
556{
557 if (scene && scene.get() == possible_parent)
558 return true;
559 if (scene)
560 return sceneIsParentOf(scene->getParent(), possible_parent);
561 return false;
562}
563} // namespace
564
565bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningScenePtr& scene) const
566{
567 return sceneIsParentOf(scene_const_, scene.get());
568}
569
570bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningSceneConstPtr& scene) const
571{
572 return sceneIsParentOf(scene_const_, scene.get());
573}
574
576{
577 // do not modify update functions while we are calling them
578 std::scoped_lock lock(update_lock_);
579
580 for (std::function<void(SceneUpdateType)>& update_callback : update_callbacks_)
581 update_callback(update_type);
582 new_scene_update_ = static_cast<SceneUpdateType>(static_cast<int>(new_scene_update_) | static_cast<int>(update_type));
583 new_scene_update_condition_.notify_all();
584}
585
586bool PlanningSceneMonitor::requestPlanningSceneState(const std::string& service_name)
587{
588 if (get_scene_service_ && get_scene_service_->get_service_name() == service_name)
589 {
590 RCLCPP_FATAL_STREAM(logger_, "requestPlanningSceneState() to self-provided service '" << service_name << '\'');
591 throw std::runtime_error("requestPlanningSceneState() to self-provided service: " + service_name);
592 }
593 // use global namespace for service
594 auto client = pnode_->create_client<moveit_msgs::srv::GetPlanningScene>(service_name);
595 auto srv = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
596 srv->components.components = srv->components.SCENE_SETTINGS | srv->components.ROBOT_STATE |
597 srv->components.ROBOT_STATE_ATTACHED_OBJECTS | srv->components.WORLD_OBJECT_NAMES |
598 srv->components.WORLD_OBJECT_GEOMETRY | srv->components.OCTOMAP |
599 srv->components.TRANSFORMS | srv->components.ALLOWED_COLLISION_MATRIX |
600 srv->components.LINK_PADDING_AND_SCALING | srv->components.OBJECT_COLORS;
601
602 // Make sure client is connected to server
603 RCLCPP_DEBUG(logger_, "Waiting for GetPlanningScene service `%s` to exist.", service_name.c_str());
604 if (client->wait_for_service(std::chrono::seconds(5)))
605 {
606 RCLCPP_DEBUG(logger_, "Sending service request to `%s`.", service_name.c_str());
607 auto service_result = client->async_send_request(srv);
608 const auto service_result_status = service_result.wait_for(std::chrono::seconds(5));
609 if (service_result_status == std::future_status::ready) // Success
610 {
611 RCLCPP_DEBUG(logger_, "Service request succeeded, applying new planning scene");
612 newPlanningSceneMessage(service_result.get()->scene);
613 return true;
614 }
615 if (service_result_status == std::future_status::timeout) // Timeout
616 {
617 RCLCPP_INFO(logger_, "GetPlanningScene service call to %s timed out. at %s:%d", service_name.c_str(), __FILE__,
618 __LINE__);
619 return false;
620 }
621 }
622
623 // If we are here, service is not available or call failed
624 RCLCPP_INFO(logger_,
625 "Failed to call service %s, have you launched move_group or called psm.providePlanningSceneService()?",
626 service_name.c_str());
627
628 return false;
629}
630
631void PlanningSceneMonitor::providePlanningSceneService(const std::string& service_name)
632{
633 // Load the service
634 get_scene_service_ = pnode_->create_service<moveit_msgs::srv::GetPlanningScene>(
635 service_name, [this](const moveit_msgs::srv::GetPlanningScene::Request::SharedPtr& req,
636 const moveit_msgs::srv::GetPlanningScene::Response::SharedPtr& res) {
637 return getPlanningSceneServiceCallback(req, res);
638 });
639}
640
641void PlanningSceneMonitor::getPlanningSceneServiceCallback(
642 const moveit_msgs::srv::GetPlanningScene::Request::SharedPtr& req,
643 const moveit_msgs::srv::GetPlanningScene::Response::SharedPtr& res)
644{
645 if (req->components.components & moveit_msgs::msg::PlanningSceneComponents::TRANSFORMS)
647
648 moveit_msgs::msg::PlanningSceneComponents all_components;
649 all_components.components = UINT_MAX; // Return all scene components if nothing is specified.
650
651 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
652 scene_->getPlanningSceneMsg(res->scene, req->components.components ? req->components : all_components);
653}
654
655void PlanningSceneMonitor::updatePublishSettings(bool publish_geom_updates, bool publish_state_updates,
656 bool publish_transform_updates, bool publish_planning_scene,
657 double publish_planning_scene_hz)
658{
660 if (publish_geom_updates)
661 {
662 event = static_cast<PlanningSceneMonitor::SceneUpdateType>(static_cast<int>(event) |
663 static_cast<int>(PlanningSceneMonitor::UPDATE_GEOMETRY));
664 }
665 if (publish_state_updates)
666 {
667 event = static_cast<PlanningSceneMonitor::SceneUpdateType>(static_cast<int>(event) |
668 static_cast<int>(PlanningSceneMonitor::UPDATE_STATE));
669 }
670 if (publish_transform_updates)
671 {
672 event = static_cast<PlanningSceneMonitor::SceneUpdateType>(
673 static_cast<int>(event) | static_cast<int>(PlanningSceneMonitor::UPDATE_TRANSFORMS));
674 }
675 if (publish_planning_scene)
676 {
677 setPlanningScenePublishingFrequency(publish_planning_scene_hz);
679 }
680 else
682}
683
684void PlanningSceneMonitor::newPlanningSceneCallback(const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene)
685{
687}
688
690{
691 bool removed = false;
692 {
693 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
694 removed = scene_->getWorldNonConst()->removeObject(scene_->OCTOMAP_NS);
695
697 {
698 octomap_monitor_->getOcTreePtr()->lockWrite();
699 octomap_monitor_->getOcTreePtr()->clear();
700 octomap_monitor_->getOcTreePtr()->unlockWrite();
701 }
702 else
703 {
704 RCLCPP_WARN(logger_, "Unable to clear octomap since no octomap monitor has been initialized");
705 } // Lift the scoped lock before calling triggerSceneUpdateEvent to avoid deadlock
706 }
707
708 if (removed)
710}
711
712bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene& scene)
713{
714 if (!scene_)
715 return false;
716
717 bool result;
718
720 std::string old_scene_name;
721 {
722 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
723 // we don't want the transform cache to update while we are potentially changing attached bodies
724 std::scoped_lock prevent_shape_cache_updates(shape_handles_lock_);
725
726 last_update_time_ = rclcpp::Clock().now();
727 last_robot_motion_time_ = scene.robot_state.joint_state.header.stamp;
728 RCLCPP_DEBUG(logger_, "scene update %f robot stamp: %f", fmod(last_update_time_.seconds(), 10.),
729 fmod(last_robot_motion_time_.seconds(), 10.));
730 old_scene_name = scene_->getName();
731
732 if (!scene.is_diff && parent_scene_)
733 {
734 // clear maintained (diff) scene_ and set the full new scene in parent_scene_ instead
735 scene_->clearDiffs();
736 result = parent_scene_->setPlanningSceneMsg(scene);
737 // There were no callbacks for individual object changes, so rebuild the octree masks
740 }
741 else
742 {
743 result = scene_->usePlanningSceneMsg(scene);
744 }
745
747 {
748 if (!scene.is_diff && scene.world.octomap.octomap.data.empty())
749 {
750 octomap_monitor_->getOcTreePtr()->lockWrite();
751 octomap_monitor_->getOcTreePtr()->clear();
752 octomap_monitor_->getOcTreePtr()->unlockWrite();
753 }
754 }
755 robot_model_ = scene_->getRobotModel();
756
758 {
759 excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
760 excludeWorldObjectsFromOctree(); // in case updates have happened to the attached bodies, put them in
761 }
762 }
763
764 // if we have a diff, try to more accurately determine the update type
765 if (scene.is_diff)
766 {
767 bool no_other_scene_upd = (scene.name.empty() || scene.name == old_scene_name) &&
768 scene.allowed_collision_matrix.entry_names.empty() && scene.link_padding.empty() &&
769 scene.link_scale.empty();
770 if (no_other_scene_upd)
771 {
772 upd = UPDATE_NONE;
773 if (!moveit::core::isEmpty(scene.world))
774 upd = static_cast<SceneUpdateType>(static_cast<int>(upd) | static_cast<int>(UPDATE_GEOMETRY));
775
776 if (!scene.fixed_frame_transforms.empty())
777 upd = static_cast<SceneUpdateType>(static_cast<int>(upd) | static_cast<int>(UPDATE_TRANSFORMS));
778
779 if (!moveit::core::isEmpty(scene.robot_state))
780 {
781 upd = static_cast<SceneUpdateType>(static_cast<int>(upd) | static_cast<int>(UPDATE_STATE));
782 if (!scene.robot_state.attached_collision_objects.empty() || !scene.robot_state.is_diff)
783 upd = static_cast<SceneUpdateType>(static_cast<int>(upd) | static_cast<int>(UPDATE_GEOMETRY));
784 }
785 }
786 }
788 return result;
789}
790
791bool PlanningSceneMonitor::processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& object,
792 const std::optional<moveit_msgs::msg::ObjectColor>& color_msg)
793{
794 if (!scene_)
795 return false;
796
798 {
799 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
800 last_update_time_ = rclcpp::Clock().now();
801 if (!scene_->processCollisionObjectMsg(*object))
802 return false;
803 if (color_msg.has_value())
804 scene_->setObjectColor(color_msg.value().id, color_msg.value().color);
805 }
807 RCLCPP_INFO(logger_, "Published update collision object");
808 return true;
809}
810
812 const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr& object)
813{
814 if (!scene_)
815 {
816 return false;
817 }
818
820 {
821 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
822 last_update_time_ = rclcpp::Clock().now();
823 if (!scene_->processAttachedCollisionObjectMsg(*object))
824 return false;
825 }
827 RCLCPP_INFO(logger_, "Published update attached");
828 return true;
829}
830
832 const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr& world)
833{
834 if (scene_)
835 {
837 {
838 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
839 last_update_time_ = rclcpp::Clock().now();
840 scene_->getWorldNonConst()->clearObjects();
841 scene_->processPlanningSceneWorldMsg(*world);
843 {
844 if (world->octomap.octomap.data.empty())
845 {
846 octomap_monitor_->getOcTreePtr()->lockWrite();
847 octomap_monitor_->getOcTreePtr()->clear();
848 octomap_monitor_->getOcTreePtr()->unlockWrite();
849 }
850 }
851 }
853 }
854}
855
857{
858 if (!octomap_monitor_)
859 return;
860
861 std::scoped_lock _(shape_handles_lock_);
862
864 const std::vector<const moveit::core::LinkModel*>& links = getRobotModel()->getLinkModelsWithCollisionGeometry();
865 auto start = std::chrono::system_clock::now();
866 bool warned = false;
867 for (const moveit::core::LinkModel* link : links)
868 {
869 std::vector<shapes::ShapeConstPtr> shapes = link->getShapes(); // copy shared ptrs on purpose
870 for (std::size_t j = 0; j < shapes.size(); ++j)
871 {
872 // merge mesh vertices up to 0.1 mm apart
873 if (shapes[j]->type == shapes::MESH)
874 {
875 shapes::Mesh* m = static_cast<shapes::Mesh*>(shapes[j]->clone());
876 m->mergeVertices(1e-4);
877 shapes[j].reset(m);
878 }
879
881 if (h)
882 link_shape_handles_[link].push_back(std::make_pair(h, j));
883 }
884
885 if (!warned && ((std::chrono::system_clock::now() - start) > std::chrono::seconds(30)))
886 {
887 RCLCPP_WARN(logger_, "It is likely there are too many vertices in collision geometry");
888 warned = true;
889 }
890 }
891}
892
894{
895 if (!octomap_monitor_)
896 return;
897
898 std::scoped_lock _(shape_handles_lock_);
899
900 for (std::pair<const moveit::core::LinkModel* const,
901 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
903 {
904 for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : link_shape_handle.second)
905 octomap_monitor_->forgetShape(it.first);
906 }
907 link_shape_handles_.clear();
908}
909
911{
912 if (!octomap_monitor_)
913 return;
914
915 std::scoped_lock _(shape_handles_lock_);
916
917 // clear information about any attached body, without referring to the AttachedBody* ptr (could be invalid)
918 for (std::pair<const moveit::core::AttachedBody* const,
919 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& attached_body_shape_handle :
921 {
922 for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : attached_body_shape_handle.second)
923 octomap_monitor_->forgetShape(it.first);
924 }
926}
927
929{
930 std::scoped_lock _(shape_handles_lock_);
931
933 // add attached objects again
934 std::vector<const moveit::core::AttachedBody*> ab;
935 scene_->getCurrentState().getAttachedBodies(ab);
936 for (const moveit::core::AttachedBody* body : ab)
938}
939
941{
942 if (!octomap_monitor_)
943 return;
944
945 std::scoped_lock _(shape_handles_lock_);
946
947 // clear information about any attached object
948 for (std::pair<const std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
949 collision_body_shape_handle : collision_body_shape_handles_)
950 {
951 for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
952 collision_body_shape_handle.second)
953 octomap_monitor_->forgetShape(it.first);
954 }
956}
957
959{
960 std::scoped_lock _(shape_handles_lock_);
961
963 for (const std::pair<const std::string, collision_detection::World::ObjectPtr>& it : *scene_->getWorld())
965}
966
968{
969 if (!octomap_monitor_)
970 return;
971
972 std::scoped_lock _(shape_handles_lock_);
973 bool found = false;
974 for (std::size_t i = 0; i < attached_body->getShapes().size(); ++i)
975 {
976 if (attached_body->getShapes()[i]->type == shapes::PLANE || attached_body->getShapes()[i]->type == shapes::OCTREE)
977 continue;
978 occupancy_map_monitor::ShapeHandle h = octomap_monitor_->excludeShape(attached_body->getShapes()[i]);
979 if (h)
980 {
981 found = true;
982 attached_body_shape_handles_[attached_body].push_back(std::make_pair(h, i));
983 }
984 }
985 if (found)
986 RCLCPP_DEBUG(logger_, "Excluding attached body '%s' from monitored octomap", attached_body->getName().c_str());
987}
988
990{
991 if (!octomap_monitor_)
992 return;
993
994 std::scoped_lock _(shape_handles_lock_);
995
996 AttachedBodyShapeHandles::iterator it = attached_body_shape_handles_.find(attached_body);
997 if (it != attached_body_shape_handles_.end())
998 {
999 for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& shape_handle : it->second)
1000 octomap_monitor_->forgetShape(shape_handle.first);
1001 RCLCPP_DEBUG(logger_, "Including attached body '%s' in monitored octomap", attached_body->getName().c_str());
1003 }
1004}
1005
1006void PlanningSceneMonitor::excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr& obj)
1007{
1008 if (!octomap_monitor_)
1009 return;
1010
1011 std::scoped_lock _(shape_handles_lock_);
1012
1013 bool found = false;
1014 for (std::size_t i = 0; i < obj->shapes_.size(); ++i)
1015 {
1016 if (obj->shapes_[i]->type == shapes::PLANE || obj->shapes_[i]->type == shapes::OCTREE)
1017 continue;
1018 occupancy_map_monitor::ShapeHandle h = octomap_monitor_->excludeShape(obj->shapes_[i]);
1019 if (h)
1020 {
1021 collision_body_shape_handles_[obj->id_].push_back(std::make_pair(h, &obj->global_shape_poses_[i]));
1022 found = true;
1023 }
1024 }
1025 if (found)
1026 RCLCPP_DEBUG(logger_, "Excluding collision object '%s' from monitored octomap", obj->id_.c_str());
1027}
1028
1029void PlanningSceneMonitor::includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr& obj)
1030{
1031 if (!octomap_monitor_)
1032 return;
1033
1034 std::scoped_lock _(shape_handles_lock_);
1035
1036 CollisionBodyShapeHandles::iterator it = collision_body_shape_handles_.find(obj->id_);
1037 if (it != collision_body_shape_handles_.end())
1038 {
1039 for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& shape_handle : it->second)
1040 octomap_monitor_->forgetShape(shape_handle.first);
1041 RCLCPP_DEBUG(logger_, "Including collision object '%s' in monitored octomap", obj->id_.c_str());
1043 }
1044}
1045
1047 bool just_attached)
1048{
1049 if (!octomap_monitor_)
1050 return;
1051
1052 if (just_attached)
1053 {
1054 excludeAttachedBodyFromOctree(attached_body);
1055 }
1056 else
1057 {
1058 includeAttachedBodyInOctree(attached_body);
1059 }
1060}
1061
1062void PlanningSceneMonitor::currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr& obj,
1064{
1065 if (!octomap_monitor_)
1066 return;
1068 return;
1069
1071 {
1073 }
1074 else if (action & collision_detection::World::DESTROY)
1075 {
1077 }
1078 else
1079 {
1082 }
1083}
1084
1085bool PlanningSceneMonitor::waitForCurrentRobotState(const rclcpp::Time& t, double wait_time)
1086{
1087 if (t.nanoseconds() == 0)
1088 return false;
1089 RCLCPP_DEBUG(logger_, "sync robot state to: %.3fs", fmod(t.seconds(), 10.));
1090
1092 {
1093 // Wait for next robot update in state monitor.
1094 bool success = current_state_monitor_->waitForCurrentState(t, wait_time);
1095
1096 /* As robot updates are passed to the planning scene only in throttled fashion, there might
1097 be still an update pending. If so, explicitly update the planning scene here.
1098 If waitForCurrentState failed, we didn't get any new state updates within wait_time. */
1099 if (success)
1100 {
1101 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1102 if (state_update_pending_) // enforce state update
1103 {
1104 state_update_pending_ = false;
1105 last_robot_state_update_wall_time_ = std::chrono::system_clock::now();
1106 lock.unlock();
1108 }
1109 return true;
1110 }
1111
1112 RCLCPP_WARN(logger_, "Failed to fetch current robot state.");
1113 return false;
1114 }
1115
1116 // Sometimes there is no state monitor. In this case state updates are received as part of scene updates only.
1117 // However, scene updates are only published if the robot actually moves. Hence we need a timeout!
1118 // As publishing planning scene updates is throttled (2Hz by default), a 1s timeout is a suitable default.
1119 auto start = node_->get_clock()->now();
1120 auto timeout = rclcpp::Duration::from_seconds(wait_time);
1121 std::shared_lock<std::shared_mutex> lock(scene_update_mutex_);
1122 rclcpp::Time prev_robot_motion_time = last_robot_motion_time_;
1123 while (last_robot_motion_time_ < t && // Wait until the state update actually reaches the scene.
1124 timeout > rclcpp::Duration(0, 0))
1125 {
1126 RCLCPP_DEBUG(logger_, "last robot motion: %f ago", (t - last_robot_motion_time_).seconds());
1127 new_scene_update_condition_.wait_for(lock, std::chrono::nanoseconds(timeout.nanoseconds()));
1128 timeout = timeout - (node_->get_clock()->now() - start); // compute remaining wait_time
1129 }
1130 bool success = last_robot_motion_time_ >= t;
1131 // suppress warning if we received an update at all
1132 if (!success && prev_robot_motion_time != last_robot_motion_time_)
1133 {
1134 RCLCPP_WARN(logger_, "Maybe failed to update robot state, time diff: %.3fs",
1135 (t - last_robot_motion_time_).seconds());
1136 }
1137
1138 RCLCPP_DEBUG(logger_, "sync done: robot motion: %f scene update: %f", (t - last_robot_motion_time_).seconds(),
1139 (t - last_update_time_).seconds());
1140 return success;
1141}
1142
1144{
1145 scene_update_mutex_.lock_shared();
1146 if (octomap_monitor_)
1147 octomap_monitor_->getOcTreePtr()->lockRead();
1148}
1149
1151{
1152 if (octomap_monitor_)
1153 octomap_monitor_->getOcTreePtr()->unlockRead();
1154 scene_update_mutex_.unlock_shared();
1155}
1156
1158{
1159 scene_update_mutex_.lock();
1160 if (octomap_monitor_)
1161 octomap_monitor_->getOcTreePtr()->lockWrite();
1162}
1163
1165{
1166 if (octomap_monitor_)
1167 octomap_monitor_->getOcTreePtr()->unlockWrite();
1168 scene_update_mutex_.unlock();
1169}
1170
1171void PlanningSceneMonitor::startSceneMonitor(const std::string& scene_topic)
1172{
1174
1175 RCLCPP_INFO(logger_, "Starting planning scene monitor");
1176 // listen for planning scene updates; these messages include transforms, so no need for filters
1177 if (!scene_topic.empty())
1178 {
1179 planning_scene_subscriber_ = pnode_->create_subscription<moveit_msgs::msg::PlanningScene>(
1180 scene_topic, rclcpp::SystemDefaultsQoS(), [this](const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene) {
1181 return newPlanningSceneCallback(scene);
1182 });
1183 RCLCPP_INFO(logger_, "Listening to '%s'", planning_scene_subscriber_->get_topic_name());
1184 }
1185}
1186
1188{
1190 {
1191 RCLCPP_INFO(logger_, "Stopping planning scene monitor");
1193 }
1194}
1195
1196bool PlanningSceneMonitor::getShapeTransformCache(const std::string& target_frame, const rclcpp::Time& target_time,
1198{
1199 try
1200 {
1201 std::scoped_lock _(shape_handles_lock_);
1202
1203 for (const std::pair<const moveit::core::LinkModel* const,
1204 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
1206 {
1207 if (tf_buffer_->canTransform(target_frame, link_shape_handle.first->getName(), target_time,
1208 shape_transform_cache_lookup_wait_time_))
1209 {
1210 Eigen::Isometry3d ttr = tf2::transformToEigen(
1211 tf_buffer_->lookupTransform(target_frame, link_shape_handle.first->getName(), target_time));
1212 for (std::size_t j = 0; j < link_shape_handle.second.size(); ++j)
1213 {
1214 cache[link_shape_handle.second[j].first] =
1215 ttr * link_shape_handle.first->getCollisionOriginTransforms()[link_shape_handle.second[j].second];
1216 }
1217 }
1218 }
1219 for (const std::pair<const moveit::core::AttachedBody* const,
1220 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>&
1221 attached_body_shape_handle : attached_body_shape_handles_)
1222 {
1223 if (tf_buffer_->canTransform(target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time,
1224 shape_transform_cache_lookup_wait_time_))
1225 {
1226 Eigen::Isometry3d transform = tf2::transformToEigen(tf_buffer_->lookupTransform(
1227 target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time));
1228 for (std::size_t k = 0; k < attached_body_shape_handle.second.size(); ++k)
1229 {
1230 cache[attached_body_shape_handle.second[k].first] =
1231 transform *
1232 attached_body_shape_handle.first->getShapePosesInLinkFrame()[attached_body_shape_handle.second[k].second];
1233 }
1234 }
1235 }
1236 {
1237 if (tf_buffer_->canTransform(target_frame, scene_->getPlanningFrame(), target_time,
1238 shape_transform_cache_lookup_wait_time_))
1239 {
1240 Eigen::Isometry3d transform =
1241 tf2::transformToEigen(tf_buffer_->lookupTransform(target_frame, scene_->getPlanningFrame(), target_time));
1242 for (const std::pair<const std::string,
1243 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
1244 collision_body_shape_handle : collision_body_shape_handles_)
1245 {
1246 for (const std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
1247 collision_body_shape_handle.second)
1248 cache[it.first] = transform * (*it.second);
1249 }
1250 }
1251 }
1252 }
1253 catch (tf2::TransformException& ex)
1254 {
1255 rclcpp::Clock steady_clock = rclcpp::Clock();
1256#pragma GCC diagnostic push
1257#pragma GCC diagnostic ignored "-Wold-style-cast"
1258 RCLCPP_ERROR_THROTTLE(logger_, steady_clock, 1000, "Transform error: %s", ex.what());
1259#pragma GCC diagnostic pop
1260 return false;
1261 }
1262 return true;
1263}
1264
1265void PlanningSceneMonitor::startWorldGeometryMonitor(const std::string& collision_objects_topic,
1266 const std::string& planning_scene_world_topic,
1267 const bool load_octomap_monitor)
1268{
1270 RCLCPP_INFO(logger_, "Starting world geometry update monitor for collision objects, attached objects, octomap "
1271 "updates.");
1272
1273 // Listen to the /collision_objects topic to detect requests to add/remove/update collision objects to/from the world
1274 if (!collision_objects_topic.empty())
1275 {
1276 collision_object_subscriber_ = pnode_->create_subscription<moveit_msgs::msg::CollisionObject>(
1277 collision_objects_topic, rclcpp::SystemDefaultsQoS(),
1278 [this](const moveit_msgs::msg::CollisionObject::ConstSharedPtr& obj) { processCollisionObjectMsg(obj); });
1279 RCLCPP_INFO(logger_, "Listening to '%s'", collision_objects_topic.c_str());
1280 }
1281
1282 if (!planning_scene_world_topic.empty())
1283 {
1284 planning_scene_world_subscriber_ = pnode_->create_subscription<moveit_msgs::msg::PlanningSceneWorld>(
1285 planning_scene_world_topic, rclcpp::SystemDefaultsQoS(),
1286 [this](const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr& world) {
1287 return newPlanningSceneWorldCallback(world);
1288 });
1289 RCLCPP_INFO(logger_, "Listening to '%s' for planning scene world geometry", planning_scene_world_topic.c_str());
1290 }
1291
1292 // Octomap monitor is optional
1293 if (load_octomap_monitor)
1294 {
1295 if (!octomap_monitor_)
1296 {
1298 std::make_unique<occupancy_map_monitor::OccupancyMapMonitor>(node_, tf_buffer_, scene_->getPlanningFrame());
1302
1303 octomap_monitor_->setTransformCacheCallback([this](const std::string& frame, const rclcpp::Time& stamp,
1305 return getShapeTransformCache(frame, stamp, cache);
1306 });
1307 octomap_monitor_->setUpdateCallback([this] { octomapUpdateCallback(); });
1308 }
1309 octomap_monitor_->startMonitor();
1310 }
1311}
1312
1314{
1316 {
1317 RCLCPP_INFO(logger_, "Stopping world geometry monitor");
1319 }
1321 {
1322 RCLCPP_INFO(logger_, "Stopping world geometry monitor");
1324 }
1325 if (octomap_monitor_)
1326 octomap_monitor_->stopMonitor();
1327}
1328
1329void PlanningSceneMonitor::startStateMonitor(const std::string& joint_states_topic,
1330 const std::string& attached_objects_topic)
1331{
1333 if (scene_)
1334 {
1336 {
1338 std::make_shared<CurrentStateMonitor>(pnode_, getRobotModel(), tf_buffer_, use_sim_time_);
1339 }
1340 current_state_monitor_->addUpdateCallback(
1341 [this](const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state) { return onStateUpdate(joint_state); });
1342 current_state_monitor_->startStateMonitor(joint_states_topic);
1343
1344 {
1345 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1346 if (dt_state_update_.count() > 0)
1347 {
1348 // ROS original: state_update_timer_.start();
1349 // TODO: re-enable WallTimer start()
1350 state_update_timer_ =
1351 pnode_->create_wall_timer(dt_state_update_, [this]() { return stateUpdateTimerCallback(); });
1352 }
1353 }
1354
1355 if (!attached_objects_topic.empty())
1356 {
1357 // using regular message filter as there's no header
1358 attached_collision_object_subscriber_ = pnode_->create_subscription<moveit_msgs::msg::AttachedCollisionObject>(
1359 attached_objects_topic, rclcpp::SystemDefaultsQoS(),
1360 [this](const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr& obj) {
1362 });
1363 RCLCPP_INFO(logger_, "Listening to '%s' for attached collision objects",
1364 attached_collision_object_subscriber_->get_topic_name());
1365 }
1366 }
1367 else
1368 RCLCPP_ERROR(logger_, "Cannot monitor robot state because planning scene is not configured");
1369}
1370
1372{
1374 current_state_monitor_->stopStateMonitor();
1377
1378 // stop must be called with state_pending_mutex_ unlocked to avoid deadlock
1379 if (state_update_timer_)
1380 state_update_timer_->cancel();
1381 {
1382 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1383 state_update_pending_ = false;
1384 }
1385}
1386
1387void PlanningSceneMonitor::onStateUpdate(const sensor_msgs::msg::JointState::ConstSharedPtr& /*joint_state */)
1388{
1389 const std::chrono::system_clock::time_point& n = std::chrono::system_clock::now();
1390 std::chrono::duration<double> dt = n - last_robot_state_update_wall_time_;
1391
1392 bool update = false;
1393 {
1394 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1395
1396 if (dt.count() < dt_state_update_.count())
1397 {
1398 state_update_pending_ = true;
1399 }
1400 else
1401 {
1402 state_update_pending_ = false;
1403 last_robot_state_update_wall_time_ = n;
1404 update = true;
1405 }
1406 }
1407 // run the state update with state_pending_mutex_ unlocked
1408 if (update)
1410}
1411
1412void PlanningSceneMonitor::stateUpdateTimerCallback()
1413{
1414 if (state_update_pending_)
1415 {
1416 bool update = false;
1417
1418 std::chrono::system_clock::time_point n = std::chrono::system_clock::now();
1419 std::chrono::duration<double> dt = n - last_robot_state_update_wall_time_;
1420
1421 {
1422 // lock for access to dt_state_update_ and state_update_pending_
1423 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1424 if (state_update_pending_ && dt.count() >= dt_state_update_.count())
1425 {
1426 state_update_pending_ = false;
1427 last_robot_state_update_wall_time_ = std::chrono::system_clock::now();
1428 auto sec = std::chrono::duration<double>(last_robot_state_update_wall_time_.time_since_epoch()).count();
1429 update = true;
1430 RCLCPP_DEBUG(logger_, "performPendingStateUpdate: %f", fmod(sec, 10));
1431 }
1432 }
1433
1434 // run the state update with state_pending_mutex_ unlocked
1435 if (update)
1436 {
1438 RCLCPP_DEBUG(logger_, "performPendingStateUpdate done");
1439 }
1440 }
1441}
1442
1444{
1445 if (!octomap_monitor_)
1446 return;
1447
1449 {
1450 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
1451 last_update_time_ = rclcpp::Clock().now();
1452 octomap_monitor_->getOcTreePtr()->lockRead();
1453 try
1454 {
1455 scene_->processOctomapPtr(octomap_monitor_->getOcTreePtr(), Eigen::Isometry3d::Identity());
1456 octomap_monitor_->getOcTreePtr()->unlockRead();
1457 }
1458 catch (...)
1459 {
1460 octomap_monitor_->getOcTreePtr()->unlockRead(); // unlock and rethrow
1461 throw;
1462 }
1463 }
1465}
1466
1468{
1469 bool update = false;
1470 if (hz > std::numeric_limits<double>::epsilon())
1471 {
1472 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1473 dt_state_update_ = std::chrono::duration<double>(1.0 / hz);
1474 // ROS original: state_update_timer_.start();
1475 // TODO: re-enable WallTimer start()
1476 state_update_timer_ = pnode_->create_wall_timer(dt_state_update_, [this]() { return stateUpdateTimerCallback(); });
1477 }
1478 else
1479 {
1480 // stop must be called with state_pending_mutex_ unlocked to avoid deadlock
1481 // ROS original: state_update_timer_.stop();
1482 // TODO: re-enable WallTimer stop()
1483 if (state_update_timer_)
1484 state_update_timer_->cancel();
1485 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1486 dt_state_update_ = std::chrono::duration<double>(0.0);
1487 if (state_update_pending_)
1488 update = true;
1489 }
1490 RCLCPP_INFO(logger_, "Updating internal planning scene state at most every %lf seconds", dt_state_update_.count());
1491
1492 if (update)
1494}
1495
1497{
1498 rclcpp::Time time = node_->now();
1499 rclcpp::Clock steady_clock = rclcpp::Clock(RCL_STEADY_TIME);
1501 {
1502 std::vector<std::string> missing;
1503 if (!current_state_monitor_->haveCompleteState(missing) &&
1504 (time - current_state_monitor_->getMonitorStartTime()).seconds() > 1.0)
1505 {
1506 std::string missing_str = fmt::format("{}", fmt::join(missing, ", "));
1507#pragma GCC diagnostic push
1508#pragma GCC diagnostic ignored "-Wold-style-cast"
1509 RCLCPP_WARN_THROTTLE(logger_, steady_clock, 1000, "The complete state of the robot is not yet known. Missing %s",
1510 missing_str.c_str());
1511#pragma GCC diagnostic pop
1512 }
1513
1514 {
1515 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
1517 RCLCPP_DEBUG(logger_, "robot state update %f", fmod(last_robot_motion_time_.seconds(), 10.));
1518 current_state_monitor_->setToCurrentState(scene_->getCurrentStateNonConst());
1519 scene_->getCurrentStateNonConst().update(); // compute all transforms
1520 }
1522 }
1523 else
1524 {
1525#pragma GCC diagnostic push
1526#pragma GCC diagnostic ignored "-Wold-style-cast"
1527 RCLCPP_ERROR_THROTTLE(logger_, steady_clock, 1000,
1528 "State monitor is not active. Unable to set the planning scene state");
1529#pragma GCC diagnostic pop
1530 }
1531}
1532
1534{
1535 std::scoped_lock lock(update_lock_);
1536 if (fn)
1537 update_callbacks_.push_back(fn);
1538}
1539
1541{
1542 std::scoped_lock lock(update_lock_);
1543 update_callbacks_.clear();
1544}
1545
1547{
1549 RCLCPP_DEBUG(logger_, "Maximum frequency for publishing a planning scene is now %lf Hz",
1551}
1552
1553void PlanningSceneMonitor::getUpdatedFrameTransforms(std::vector<geometry_msgs::msg::TransformStamped>& transforms)
1554{
1555 const std::string& target = getRobotModel()->getModelFrame();
1556
1557 std::vector<std::string> all_frame_names;
1558 tf_buffer_->_getFrameStrings(all_frame_names);
1559 for (const std::string& all_frame_name : all_frame_names)
1560 {
1561 if (all_frame_name == target || getRobotModel()->hasLinkModel(all_frame_name))
1562 continue;
1563
1564 geometry_msgs::msg::TransformStamped f;
1565 try
1566 {
1567 f = tf_buffer_->lookupTransform(target, all_frame_name, tf2::TimePointZero);
1568 }
1569 catch (tf2::TransformException& ex)
1570 {
1571 RCLCPP_WARN(logger_, "Unable to transform object from frame '%s' to planning frame'%s' (%s)",
1572 all_frame_name.c_str(), target.c_str(), ex.what());
1573 continue;
1574 }
1575 f.header.frame_id = all_frame_name;
1576 f.child_frame_id = target;
1577 transforms.push_back(f);
1578 }
1579}
1580
1582{
1583 if (scene_)
1584 {
1585 std::vector<geometry_msgs::msg::TransformStamped> transforms;
1586 getUpdatedFrameTransforms(transforms);
1587 {
1588 std::unique_lock<std::shared_mutex> ulock(scene_update_mutex_);
1589 scene_->getTransformsNonConst().setTransforms(transforms);
1590 last_update_time_ = rclcpp::Clock().now();
1591 }
1593 }
1594}
1595
1597{
1598 if (octomap_monitor_)
1599 octomap_monitor_->publishDebugInformation(flag);
1600}
1601
1602void PlanningSceneMonitor::configureCollisionMatrix(const planning_scene::PlanningScenePtr& scene)
1603{
1604 if (!scene || robot_description_.empty())
1605 return;
1606 // TODO: Uncomment when XmlRpc is refactored
1607 // collision_detection::AllowedCollisionMatrix& acm = scene->getAllowedCollisionMatrixNonConst();
1608
1609 // read overriding values from the param server
1610
1611 // first we do default collision operations
1612 if (!node_->has_parameter(robot_description_ + "_planning.default_collision_operations"))
1613 {
1614 RCLCPP_DEBUG(logger_, "No additional default collision operations specified");
1615 }
1616 else
1617 {
1618 RCLCPP_DEBUG(logger_, "Reading additional default collision operations");
1619
1620 // TODO: codebase wide refactoring for XmlRpc
1621 // XmlRpc::XmlRpcValue coll_ops;
1622 // node_->get_parameter(robot_description_ + "_planning/default_collision_operations", coll_ops);
1623
1624 // if (coll_ops.getType() != XmlRpc::XmlRpcValue::TypeArray)
1625 // {
1626 // RCLCPP_WARN(logger_, "default_collision_operations is not an array");
1627 // return;
1628 // }
1629
1630 // if (coll_ops.size() == 0)
1631 // {
1632 // RCLCPP_WARN(logger_, "No collision operations in default collision operations");
1633 // return;
1634 // }
1635
1636 // for (int i = 0; i < coll_ops.size(); ++i) // NOLINT(modernize-loop-convert)
1637 // {
1638 // if (!coll_ops[i].hasMember("object1") || !coll_ops[i].hasMember("object2") ||
1639 // !coll_ops[i].hasMember("operation"))
1640 // {
1641 // RCLCPP_WARN(logger_, "All collision operations must have two objects and an operation");
1642 // continue;
1643 // }
1644 // acm.setEntry(std::string(coll_ops[i]["object1"]), std::string(coll_ops[i]["object2"]),
1645 // std::string(coll_ops[i]["operation"]) == "disable");
1646 // }
1647 }
1648}
1649
1651{
1652 if (robot_description_.empty())
1653 {
1654 default_robot_padd_ = 0.0;
1658 return;
1659 }
1660
1661 // Ensure no leading slash creates a bad param server address
1662 static const std::string ROBOT_DESCRIPTION =
1664
1665 node_->get_parameter_or(ROBOT_DESCRIPTION + "_planning.default_robot_padding", default_robot_padd_, 0.0);
1666 node_->get_parameter_or(ROBOT_DESCRIPTION + "_planning.default_robot_scale", default_robot_scale_, 1.0);
1667 node_->get_parameter_or(ROBOT_DESCRIPTION + "_planning.default_object_padding", default_object_padd_, 0.0);
1668 node_->get_parameter_or(ROBOT_DESCRIPTION + "_planning.default_attached_padding", default_attached_padd_, 0.0);
1669 default_robot_link_padd_ = std::map<std::string, double>();
1670 default_robot_link_scale_ = std::map<std::string, double>();
1671 // TODO: enable parameter type support to std::map
1672 // node_->get_parameter_or(robot_description + "_planning/default_robot_link_padding", default_robot_link_padd_,
1673 // std::map<std::string, double>());
1674 // node_->get_parameter_or(robot_description + "_planning/default_robot_link_scale", default_robot_link_scale_,
1675 // std::map<std::string, double>());
1676
1677 RCLCPP_DEBUG_STREAM(logger_, "Loaded " << default_robot_link_padd_.size() << " default link paddings");
1678 RCLCPP_DEBUG_STREAM(logger_, "Loaded " << default_robot_link_scale_.size() << " default link scales");
1679}
1680} // namespace planning_scene_monitor
void setupScene(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene)
Fetch plugin name from parameter server and activate the plugin for the given scene.
std::shared_lock< std::shared_mutex > ReadLock
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition world.h:268
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
Definition world.h:304
This may be thrown during construction of objects if errors occur.
Definition exceptions.h:46
Object defining bodies that can be attached to robot links.
const std::string & getName() const
Get the name of the attached body.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
This class maintains the representation of the environment as seen by a planning instance....
static const std::string OCTOMAP_NS
PlanningSceneMonitor Subscribes to the topic planning_scene.
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
void lockSceneRead()
Lock the scene for reading (multiple threads can lock for reading at the same time)
void lockSceneWrite()
Lock the scene for writing (only one thread can lock for writing and no other thread can lock for rea...
void unlockSceneRead()
Unlock the scene from reading (multiple threads can lock for reading at the same time)
static const std::string DEFAULT_PLANNING_SCENE_SERVICE
The name of the service used by default for requesting full planning scene state.
double default_attached_padd_
default attached padding
void currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr &object, collision_detection::World::Action action)
Callback for a change in the world maintained by the planning scene.
std::unique_ptr< occupancy_map_monitor::OccupancyMapMonitor > octomap_monitor_
std::map< std::string, double > default_robot_link_padd_
default robot link padding
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
The name of the topic used by default for receiving collision objects in the world.
void configureDefaultPadding()
Configure the default padding.
PlanningSceneMonitor(const PlanningSceneMonitor &)=delete
PlanningSceneMonitor cannot be copy-constructed.
rclcpp::Subscription< moveit_msgs::msg::AttachedCollisionObject >::SharedPtr attached_collision_object_subscriber_
void stopPublishingPlanningScene()
Stop publishing the maintained planning scene.
void excludeAttachedBodyFromOctree(const moveit::core::AttachedBody *attached_body)
void addUpdateCallback(const std::function< void(SceneUpdateType)> &fn)
Add a function to be called when an update to the scene is received.
bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene &scene)
void setPlanningScenePublishingFrequency(double hz)
Set the maximum frequency at which planning scenes are being published.
bool processAttachedCollisionObjectMsg(const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr &attached_collision_object_msg)
void includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr &obj)
rclcpp::Service< moveit_msgs::srv::GetPlanningScene >::SharedPtr get_scene_service_
void initialize(const planning_scene::PlanningScenePtr &scene)
Initialize the planning scene monitor.
void getMonitoredTopics(std::vector< std::string > &topics) const
Get the topic names that the monitor is listening to.
void triggerSceneUpdateEvent(SceneUpdateType update_type)
This function is called every time there is a change to the planning scene.
void newPlanningSceneWorldCallback(const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr &world)
Callback for a new planning scene world.
planning_scene::PlanningSceneConstPtr scene_const_
rclcpp::Subscription< moveit_msgs::msg::CollisionObject >::SharedPtr collision_object_subscriber_
void includeAttachedBodyInOctree(const moveit::core::AttachedBody *attached_body)
void octomapUpdateCallback()
Callback for octomap updates.
rclcpp::Subscription< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_subscriber_
void clearUpdateCallbacks()
Clear the functions to be called when an update to the scene is received.
void providePlanningSceneService(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Create an optional service for getting the complete planning scene This is useful for satisfying the ...
std::shared_mutex scene_update_mutex_
if diffs are monitored, this is the pointer to the parent scene
const moveit::core::RobotModelConstPtr & getRobotModel() const
void setStateUpdateFrequency(double hz)
Update the scene using the monitored state at a specified frequency, in Hz. This function has an effe...
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
void stopWorldGeometryMonitor()
Stop the world geometry monitor.
void startStateMonitor(const std::string &joint_states_topic=DEFAULT_JOINT_STATES_TOPIC, const std::string &attached_objects_topic=DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC)
Start the current state monitor.
@ UPDATE_STATE
The state in the monitored scene was updated.
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
@ UPDATE_TRANSFORMS
The maintained set of fixed transforms in the monitored scene was updated.
std::shared_ptr< rclcpp::executors::SingleThreadedExecutor > private_executor_
bool getShapeTransformCache(const std::string &target_frame, const rclcpp::Time &target_time, occupancy_map_monitor::ShapeTransformCache &cache) const
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
void startPublishingPlanningScene(SceneUpdateType event, const std::string &planning_scene_topic=MONITORED_PLANNING_SCENE_TOPIC)
Start publishing the maintained planning scene. The first message set out is a complete planning scen...
bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr &collision_object_msg, const std::optional< moveit_msgs::msg::ObjectColor > &color_msg=std::nullopt)
bool waitForCurrentRobotState(const rclcpp::Time &t, double wait_time=1.)
Wait for robot state to become more recent than time t.
std::map< std::string, double > default_robot_link_scale_
default robot link scale
void updateSceneWithCurrentState()
Update the scene using the monitored state. This function is automatically called when an update to t...
rclcpp::Time last_robot_motion_time_
Last time the state was updated.
std::string monitor_name_
The name of this scene monitor.
bool updatesScene(const planning_scene::PlanningSceneConstPtr &scene) const
Return true if the scene scene can be updated directly or indirectly by this monitor....
std::recursive_mutex update_lock_
lock access to update_callbacks_
rclcpp::Time last_update_time_
mutex for stored scene
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Request a full planning scene state using a service call Be careful not to use this in conjunction wi...
void monitorDiffs(bool flag)
By default, the maintained planning scene does not reason about diffs. When the flag passed in is tru...
void currentStateAttachedBodyUpdateCallback(moveit::core::AttachedBody *attached_body, bool just_attached)
Callback for a change for an attached object of the current state of the planning scene.
std::unique_ptr< std::thread > publish_planning_scene_
std::shared_ptr< rclcpp::Node > node_
Last time the robot has moved.
void configureCollisionMatrix(const planning_scene::PlanningScenePtr &scene)
Configure the collision matrix for a particular scene.
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
Start the OccupancyMapMonitor and listening for:
rclcpp::Publisher< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_publisher_
static const std::string DEFAULT_JOINT_STATES_TOPIC
The name of the topic used by default for receiving joint states.
void excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr &obj)
std::vector< std::function< void(SceneUpdateType)> > update_callbacks_
void updateFrameTransforms()
Update the transforms for the frames that are not part of the kinematic model using tf....
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
void unlockSceneWrite()
Lock the scene from writing (only one thread can lock for writing and no other thread can lock for re...
rclcpp::Subscription< moveit_msgs::msg::PlanningSceneWorld >::SharedPtr planning_scene_world_subscriber_
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
void update(moveit::core::RobotState *self, bool force, std::string &category)
Main namespace for MoveIt.
Definition exceptions.h:43
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
This namespace includes the central class for representing planning contexts.
Definition world.h:49