86 UPDATE_TRANSFORMS = 2,
93 UPDATE_SCENE = 8 + UPDATE_STATE + UPDATE_TRANSFORMS + UPDATE_GEOMETRY
124 const std::string& name =
"");
130 PlanningSceneMonitor(
const rclcpp::Node::SharedPtr& node,
const robot_model_loader::RobotModelLoaderPtr& rml,
131 const std::string& name =
"");
138 PlanningSceneMonitor(
const rclcpp::Node::SharedPtr& node,
const planning_scene::PlanningScenePtr& scene,
139 const std::string& robot_description,
const std::string& name =
"");
146 PlanningSceneMonitor(
const rclcpp::Node::SharedPtr& node,
const planning_scene::PlanningScenePtr& scene,
147 const robot_model_loader::RobotModelLoaderPtr& rml,
const std::string& name =
"");
154 return monitor_name_;
196 planning_scene::PlanningScenePtr
197 copyPlanningScene(
const moveit_msgs::msg::PlanningScene& diff = moveit_msgs::msg::PlanningScene());
203 bool updatesScene(
const planning_scene::PlanningSceneConstPtr& scene)
const;
209 bool updatesScene(
const planning_scene::PlanningScenePtr& scene)
const;
215 return robot_description_;
221 return default_robot_padd_;
227 return default_robot_scale_;
233 return default_object_padd_;
239 return default_attached_padd_;
253 void monitorDiffs(
bool flag);
258 void startPublishingPlanningScene(SceneUpdateType event,
259 const std::string& planning_scene_topic = MONITORED_PLANNING_SCENE_TOPIC);
262 void stopPublishingPlanningScene();
265 void setPlanningScenePublishingFrequency(
double hz);
270 return publish_planning_scene_frequency_;
277 return current_state_monitor_;
282 return current_state_monitor_;
290 void updateFrameTransforms();
295 void startStateMonitor(
const std::string& joint_states_topic = DEFAULT_JOINT_STATES_TOPIC,
296 const std::string& attached_objects_topic = DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC);
299 void stopStateMonitor();
305 void updateSceneWithCurrentState(
bool skip_update_if_locked =
false);
312 void setStateUpdateFrequency(
double hz);
317 if (dt_state_update_.count() > 0.0)
319 return 1.0 / dt_state_update_.count();
330 void startSceneMonitor(
const std::string& scene_topic = DEFAULT_PLANNING_SCENE_TOPIC);
339 bool requestPlanningSceneState(
const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE);
348 void providePlanningSceneService(
const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE);
351 void stopSceneMonitor();
361 void startWorldGeometryMonitor(
const std::string& collision_objects_topic = DEFAULT_COLLISION_OBJECT_TOPIC,
362 const std::string& planning_scene_world_topic = DEFAULT_PLANNING_SCENE_WORLD_TOPIC,
363 const bool load_octomap_monitor =
true);
366 void stopWorldGeometryMonitor();
369 void addUpdateCallback(
const std::function<
void(SceneUpdateType)>& fn);
372 void clearUpdateCallbacks();
375 void getMonitoredTopics(std::vector<std::string>& topics)
const;
380 return last_update_time_;
383 void publishDebugInformation(
bool flag);
386 void triggerSceneUpdateEvent(SceneUpdateType update_type);
393 bool waitForCurrentRobotState(
const rclcpp::Time& t,
double wait_time = 1.);
398 bool newPlanningSceneMessage(
const moveit_msgs::msg::PlanningScene& scene);
401 bool processCollisionObjectMsg(
const moveit_msgs::msg::CollisionObject::ConstSharedPtr& collision_object_msg,
402 const std::optional<moveit_msgs::msg::ObjectColor>& color_msg = std::nullopt);
405 bool processAttachedCollisionObjectMsg(
406 const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr& attached_collision_object_msg);
412 void initialize(
const planning_scene::PlanningScenePtr& scene);
415 void lockSceneRead();
418 void unlockSceneRead();
422 void lockSceneWrite();
426 void unlockSceneWrite();
429 void configureCollisionMatrix(
const planning_scene::PlanningScenePtr& scene);
432 void configureDefaultPadding();
435 void newPlanningSceneWorldCallback(
const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr& world);
438 void octomapUpdateCallback();
444 void currentWorldObjectUpdateCallback(
const collision_detection::World::ObjectConstPtr&
object,
447 void includeRobotLinksInOctree();
448 void excludeRobotLinksFromOctree();
450 void excludeWorldObjectsFromOctree();
451 void includeWorldObjectsInOctree();
452 void excludeWorldObjectFromOctree(
const collision_detection::World::ObjectConstPtr& obj);
453 void includeWorldObjectInOctree(
const collision_detection::World::ObjectConstPtr& obj);
455 void excludeAttachedBodiesFromOctree();
456 void includeAttachedBodiesInOctree();
460 bool getShapeTransformCache(
const std::string& target_frame,
const rclcpp::Time& target_time,
473 std::shared_ptr<rclcpp::Node>
node_;
526 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >
529 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >;
531 std::map<std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*> > >;
544 void getUpdatedFrameTransforms(std::vector<geometry_msgs::msg::TransformStamped>& transforms);
547 void scenePublishingThread();
550 void onStateUpdate(
const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state);
553 void stateUpdateTimerCallback();
556 void newPlanningSceneCallback(
const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene);
559 void getPlanningSceneServiceCallback(
const moveit_msgs::srv::GetPlanningScene::Request::SharedPtr& req,
560 const moveit_msgs::srv::GetPlanningScene::Response::SharedPtr& res);
562 void updatePublishSettings(
bool publish_geom_updates,
bool publish_state_updates,
bool publish_transform_updates,
563 bool publish_planning_scene,
double publish_planning_scene_hz);
566 std::atomic<bool> state_update_pending_;
569 std::mutex state_update_mutex_;
574 std::chrono::system_clock::time_point last_robot_state_update_wall_time_;
578 std::chrono::duration<double> dt_state_update_;
583 rclcpp::Duration shape_transform_cache_lookup_wait_time_;
588 rclcpp::TimerBase::SharedPtr state_update_timer_;
590 robot_model_loader::RobotModelLoaderPtr rm_loader_;
591 moveit::core::RobotModelConstPtr robot_model_;
595 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr callback_handler_;
602 rclcpp::Logger logger_;