moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_scene_monitor.h
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
37#pragma once
38
39#include <rclcpp/rclcpp.hpp>
40#include <tf2_ros/buffer.h>
41#include <tf2_ros/transform_listener.h>
48#include <moveit_msgs/srv/get_planning_scene.hpp>
49#include <memory>
50#include <thread>
51#include <shared_mutex>
52#include <mutex>
53#include <thread>
54
55#include <moveit_planning_scene_monitor_export.h>
56
58{
59MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, ConstPtr, WeakPtr... etc
60
64class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor
65{
66public:
71
76
78 {
80 UPDATE_NONE = 0,
81
83 UPDATE_STATE = 1,
84
86 UPDATE_TRANSFORMS = 2,
87
90 UPDATE_GEOMETRY = 4,
91
93 UPDATE_SCENE = 8 + UPDATE_STATE + UPDATE_TRANSFORMS + UPDATE_GEOMETRY
94 };
95
97 static const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states"
98
100 static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object"
101
103 static const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object"
104
107 static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world"
108
110 static const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene"
111
113 static const std::string DEFAULT_PLANNING_SCENE_SERVICE; // "/get_planning_scene"
114
117 static const std::string MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene"
118
123 PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const std::string& robot_description,
124 const std::string& name = "");
125
130 PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const robot_model_loader::RobotModelLoaderPtr& rml,
131 const std::string& name = "");
132
138 PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningScenePtr& scene,
139 const std::string& robot_description, const std::string& name = "");
140
146 PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningScenePtr& scene,
147 const robot_model_loader::RobotModelLoaderPtr& rml, const std::string& name = "");
148
150
152 const std::string& getName() const
153 {
154 return monitor_name_;
155 }
156
158 const robot_model_loader::RobotModelLoaderPtr& getRobotModelLoader() const
159 {
160 return rm_loader_;
161 }
162
163 const moveit::core::RobotModelConstPtr& getRobotModel() const
164 {
165 return robot_model_;
166 }
167
182 const planning_scene::PlanningScenePtr& getPlanningScene()
183 {
184 return scene_;
185 }
186
190 const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
191 {
192 return scene_const_;
193 }
194
199 bool updatesScene(const planning_scene::PlanningSceneConstPtr& scene) const;
200
205 bool updatesScene(const planning_scene::PlanningScenePtr& scene) const;
206
209 const std::string& getRobotDescription() const
210 {
211 return robot_description_;
212 }
213
216 {
217 return default_robot_padd_;
218 }
219
221 double getDefaultRobotScale() const
222 {
223 return default_robot_scale_;
224 }
225
228 {
229 return default_object_padd_;
230 }
231
234 {
235 return default_attached_padd_;
236 }
237
239 const std::shared_ptr<tf2_ros::Buffer>& getTFClient() const
240 {
241 return tf_buffer_;
242 }
243
249 void monitorDiffs(bool flag);
250
254 void startPublishingPlanningScene(SceneUpdateType event,
255 const std::string& planning_scene_topic = MONITORED_PLANNING_SCENE_TOPIC);
256
258 void stopPublishingPlanningScene();
259
261 void setPlanningScenePublishingFrequency(double hz);
262
265 {
266 return publish_planning_scene_frequency_;
267 }
268
271 const CurrentStateMonitorPtr& getStateMonitor() const
272 {
273 return current_state_monitor_;
274 }
275
276 CurrentStateMonitorPtr& getStateMonitorNonConst()
277 {
278 return current_state_monitor_;
279 }
280
286 void updateFrameTransforms();
287
291 void startStateMonitor(const std::string& joint_states_topic = DEFAULT_JOINT_STATES_TOPIC,
292 const std::string& attached_objects_topic = DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC);
293
295 void stopStateMonitor();
296
300 void updateSceneWithCurrentState();
301
307 void setStateUpdateFrequency(double hz);
308
311 {
312 if (dt_state_update_.count() > 0.0)
313 {
314 return 1.0 / dt_state_update_.count();
315 }
316 else
317 {
318 return 0.0;
319 }
320 }
321
325 void startSceneMonitor(const std::string& scene_topic = DEFAULT_PLANNING_SCENE_TOPIC);
326
334 bool requestPlanningSceneState(const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE);
335
343 void providePlanningSceneService(const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE);
344
346 void stopSceneMonitor();
347
356 void startWorldGeometryMonitor(const std::string& collision_objects_topic = DEFAULT_COLLISION_OBJECT_TOPIC,
357 const std::string& planning_scene_world_topic = DEFAULT_PLANNING_SCENE_WORLD_TOPIC,
358 const bool load_octomap_monitor = true);
359
361 void stopWorldGeometryMonitor();
362
364 void addUpdateCallback(const std::function<void(SceneUpdateType)>& fn);
365
367 void clearUpdateCallbacks();
368
370 void getMonitoredTopics(std::vector<std::string>& topics) const;
371
373 const rclcpp::Time& getLastUpdateTime() const
374 {
375 return last_update_time_;
376 }
377
378 void publishDebugInformation(bool flag);
379
381 void triggerSceneUpdateEvent(SceneUpdateType update_type);
382
388 bool waitForCurrentRobotState(const rclcpp::Time& t, double wait_time = 1.);
389
390 void clearOctomap();
391
392 // Called to update the planning scene with a new message.
393 bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene& scene);
394
395 // Called to update a collision object in the planning scene.
396 bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& collision_object_msg,
397 const std::optional<moveit_msgs::msg::ObjectColor>& color_msg = std::nullopt);
398
399 // Called to update an attached collision object in the planning scene.
400 bool processAttachedCollisionObjectMsg(
401 const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr& attached_collision_object_msg);
402
403protected:
407 void initialize(const planning_scene::PlanningScenePtr& scene);
408
410 void lockSceneRead();
411
413 void unlockSceneRead();
414
417 void lockSceneWrite();
418
421 void unlockSceneWrite();
422
424 void configureCollisionMatrix(const planning_scene::PlanningScenePtr& scene);
425
427 void configureDefaultPadding();
428
430 void newPlanningSceneWorldCallback(const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr& world);
431
433 void octomapUpdateCallback();
434
436 void currentStateAttachedBodyUpdateCallback(moveit::core::AttachedBody* attached_body, bool just_attached);
437
439 void currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr& object,
441
442 void includeRobotLinksInOctree();
443 void excludeRobotLinksFromOctree();
444
445 void excludeWorldObjectsFromOctree();
446 void includeWorldObjectsInOctree();
447 void excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr& obj);
448 void includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr& obj);
449
450 void excludeAttachedBodiesFromOctree();
451 void includeAttachedBodiesInOctree();
452 void excludeAttachedBodyFromOctree(const moveit::core::AttachedBody* attached_body);
453 void includeAttachedBodyInOctree(const moveit::core::AttachedBody* attached_body);
454
455 bool getShapeTransformCache(const std::string& target_frame, const rclcpp::Time& target_time,
457
459 std::string monitor_name_;
460
461 planning_scene::PlanningScenePtr scene_;
462 planning_scene::PlanningSceneConstPtr scene_const_;
463 planning_scene::PlanningScenePtr parent_scene_;
464 std::shared_mutex scene_update_mutex_;
465 rclcpp::Time last_update_time_;
467
468 std::shared_ptr<rclcpp::Node> node_;
469
470 // TODO: (anasarrak) callbacks on ROS2?
471 // https://answers.ros.org/question/300874/how-do-you-use-callbackgroups-as-a-replacement-for-callbackqueues-in-ros2/
472 // ros::CallbackQueue queue_;
473 std::shared_ptr<rclcpp::Node> pnode_;
474 std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> private_executor_;
476
477 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
478 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
479
481
491 std::map<std::string, double> default_robot_link_padd_;
493 std::map<std::string, double> default_robot_link_scale_;
494
495 // variables for planning scene publishing
496 rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_publisher_;
497 std::unique_ptr<std::thread> publish_planning_scene_;
500 std::atomic<SceneUpdateType> new_scene_update_;
501 std::condition_variable_any new_scene_update_condition_;
502
503 // subscribe to various sources of data
504 rclcpp::Subscription<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_subscriber_;
505 rclcpp::Subscription<moveit_msgs::msg::PlanningSceneWorld>::SharedPtr planning_scene_world_subscriber_;
506
507 rclcpp::Subscription<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr attached_collision_object_subscriber_;
508 rclcpp::Subscription<moveit_msgs::msg::CollisionObject>::SharedPtr collision_object_subscriber_;
509
510 // provide an optional service to get the full planning scene state
511 // this is used by MoveGroup and related application nodes
512 rclcpp::Service<moveit_msgs::srv::GetPlanningScene>::SharedPtr get_scene_service_;
513
514 // include a octomap monitor
515 std::unique_ptr<occupancy_map_monitor::OccupancyMapMonitor> octomap_monitor_;
516
517 // include a current state monitor
518 CurrentStateMonitorPtr current_state_monitor_;
519
520 typedef std::map<const moveit::core::LinkModel*,
521 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >
524 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >;
526 std::map<std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*> > >;
527
531 mutable std::recursive_mutex shape_handles_lock_;
532
534 std::recursive_mutex update_lock_;
535 std::vector<std::function<void(SceneUpdateType)> > update_callbacks_;
537
538private:
539 void getUpdatedFrameTransforms(std::vector<geometry_msgs::msg::TransformStamped>& transforms);
540
541 // publish planning scene update diffs (runs in its own thread)
542 void scenePublishingThread();
543
544 // called by current_state_monitor_ when robot state (as monitored on joint state topic) changes
545 void onStateUpdate(const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state);
546
547 // called by state_update_timer_ when a state update it pending
548 void stateUpdateTimerCallback();
549
550 // Callback for a new planning scene msg
551 void newPlanningSceneCallback(const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene);
552
553 // Callback for requesting the full planning scene via service
554 void getPlanningSceneServiceCallback(const moveit_msgs::srv::GetPlanningScene::Request::SharedPtr& req,
555 const moveit_msgs::srv::GetPlanningScene::Response::SharedPtr& res);
556
557 void updatePublishSettings(bool publish_geom_updates, bool publish_state_updates, bool publish_transform_updates,
558 bool publish_planning_scene, double publish_planning_scene_hz);
559
560 // Lock for state_update_pending_ and dt_state_update_
561 std::mutex state_pending_mutex_;
562
564 // This field is protected by state_pending_mutex_
565 volatile bool state_update_pending_;
566
568 // This field is protected by state_pending_mutex_
569 std::chrono::duration<double> dt_state_update_; // 1hz
570
572 // Setting this to a non-zero value resolves issues when the sensor data is
573 // arriving so fast that it is preceding the transform state.
574 rclcpp::Duration shape_transform_cache_lookup_wait_time_;
575
577 // Check if last_state_update_ is true and if so call updateSceneWithCurrentState()
578 // Not safe to access from callback functions.
579
580 rclcpp::TimerBase::SharedPtr state_update_timer_;
581
583 // Only access this from callback functions (and constructor)
584 std::chrono::system_clock::time_point last_robot_state_update_wall_time_;
585
586 robot_model_loader::RobotModelLoaderPtr rm_loader_;
587 moveit::core::RobotModelConstPtr robot_model_;
588
590
591 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr callback_handler_;
592
593 bool use_sim_time_;
594
597
598 rclcpp::Logger logger_;
599};
600
623{
624public:
625 LockedPlanningSceneRO(const PlanningSceneMonitorPtr& planning_scene_monitor)
627 {
628 initialize(true);
629 }
630
631 const PlanningSceneMonitorPtr& getPlanningSceneMonitor()
632 {
634 }
635
636 operator bool() const
637 {
638 return planning_scene_monitor_ && planning_scene_monitor_->getPlanningScene();
639 }
640
641 operator const planning_scene::PlanningSceneConstPtr&() const
642 {
643 return static_cast<const PlanningSceneMonitor*>(planning_scene_monitor_.get())->getPlanningScene();
644 }
645
646 const planning_scene::PlanningSceneConstPtr& operator->() const
647 {
648 return static_cast<const PlanningSceneMonitor*>(planning_scene_monitor_.get())->getPlanningScene();
649 }
650
651protected:
652 LockedPlanningSceneRO(const PlanningSceneMonitorPtr& planning_scene_monitor, bool read_only)
654 {
655 initialize(read_only);
656 }
657
658 void initialize(bool read_only)
659 {
661 lock_ = std::make_shared<SingleUnlock>(planning_scene_monitor_.get(), read_only);
662 }
663
665
666 // we use this struct so that lock/unlock are called only once
667 // even if the LockedPlanningScene instance is copied around
696
697 PlanningSceneMonitorPtr planning_scene_monitor_;
698 SingleUnlockPtr lock_;
699};
700
723{
724public:
725 LockedPlanningSceneRW(const PlanningSceneMonitorPtr& planning_scene_monitor)
727 {
728 }
729
730 operator const planning_scene::PlanningScenePtr&()
731 {
732 return planning_scene_monitor_->getPlanningScene();
733 }
734
735 const planning_scene::PlanningScenePtr& operator->()
736 {
737 return planning_scene_monitor_->getPlanningScene();
738 }
739};
740} // namespace planning_scene_monitor
#define MOVEIT_CLASS_FORWARD(C)
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition world.h:268
Object defining bodies that can be attached to robot links.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
LockedPlanningSceneRO(const PlanningSceneMonitorPtr &planning_scene_monitor, bool read_only)
LockedPlanningSceneRO(const PlanningSceneMonitorPtr &planning_scene_monitor)
const planning_scene::PlanningSceneConstPtr & operator->() const
const PlanningSceneMonitorPtr & getPlanningSceneMonitor()
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
const planning_scene::PlanningScenePtr & operator->()
LockedPlanningSceneRW(const PlanningSceneMonitorPtr &planning_scene_monitor)
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
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.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Avoid this function! Returns an unsafe pointer to the current planning scene.
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
The name of the topic used by default for receiving collision objects in the world.
PlanningSceneMonitor(const PlanningSceneMonitor &)=delete
PlanningSceneMonitor cannot be copy-constructed.
rclcpp::Subscription< moveit_msgs::msg::AttachedCollisionObject >::SharedPtr attached_collision_object_subscriber_
std::map< std::string, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d * > > > CollisionBodyShapeHandles
rclcpp::Service< moveit_msgs::srv::GetPlanningScene >::SharedPtr get_scene_service_
std::map< const moveit::core::LinkModel *, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, std::size_t > > > LinkShapeHandles
double getDefaultAttachedObjectPadding() const
Get the default attached padding.
planning_scene::PlanningSceneConstPtr scene_const_
PlanningSceneMonitor & operator=(const PlanningSceneMonitor &)=delete
PlanningSceneMonitor cannot be copy-assigned.
rclcpp::Subscription< moveit_msgs::msg::CollisionObject >::SharedPtr collision_object_subscriber_
rclcpp::Subscription< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_subscriber_
double getDefaultRobotPadding() const
Get the default robot padding.
std::shared_mutex scene_update_mutex_
if diffs are monitored, this is the pointer to the parent scene
const moveit::core::RobotModelConstPtr & getRobotModel() const
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
double getStateUpdateFrequency() const
Get the maximum frequency (Hz) at which the current state of the planning scene is updated.
std::shared_ptr< rclcpp::executors::SingleThreadedExecutor > private_executor_
const rclcpp::Time & getLastUpdateTime() const
Return the time when the last update was made to the planning scene (by any monitor)
const CurrentStateMonitorPtr & getStateMonitor() const
Get the stored instance of the stored current state monitor.
std::map< const moveit::core::AttachedBody *, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, std::size_t > > > AttachedBodyShapeHandles
double getDefaultObjectPadding() const
Get the default object padding.
std::map< std::string, double > default_robot_link_scale_
default robot link scale
rclcpp::Time last_robot_motion_time_
Last time the state was updated.
double getDefaultRobotScale() const
Get the default robot scaling.
std::string monitor_name_
The name of this scene monitor.
std::recursive_mutex update_lock_
lock access to update_callbacks_
rclcpp::Time last_update_time_
mutex for stored scene
const std::string & getRobotDescription() const
Get the stored robot description.
const std::string & getName() const
Get the name of this monitor.
const robot_model_loader::RobotModelLoaderPtr & getRobotModelLoader() const
Get the user kinematic model loader.
std::unique_ptr< std::thread > publish_planning_scene_
std::shared_ptr< rclcpp::Node > node_
Last time the robot has moved.
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.
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
const std::shared_ptr< tf2_ros::Buffer > & getTFClient() const
Get the instance of the TF client that was passed to the constructor of this class.
std::vector< std::function< void(SceneUpdateType)> > update_callbacks_
double getPlanningScenePublishingFrequency() const
Get the maximum frequency at which planning scenes are published (Hz)
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_
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
SingleUnlock(PlanningSceneMonitor *planning_scene_monitor, bool read_only)