From 4dc527b185216b74a4fcf05d62a9927c04e0aede Mon Sep 17 00:00:00 2001 From: Joseph Schornak Date: Thu, 3 Feb 2022 21:56:09 -0500 Subject: [PATCH] Explicitly set is_primary_planning_scene_monitor in Servo example config --- moveit_ros/moveit_servo/config/panda_simulated_config.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/moveit_ros/moveit_servo/config/panda_simulated_config.yaml b/moveit_ros/moveit_servo/config/panda_simulated_config.yaml index 1771d10611..e29559f534 100644 --- a/moveit_ros/moveit_servo/config/panda_simulated_config.yaml +++ b/moveit_ros/moveit_servo/config/panda_simulated_config.yaml @@ -28,6 +28,12 @@ publish_joint_accelerations: false ## Plugins for smoothing outgoing commands smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin" +# If is_primary_planning_scene_monitor is set to true, the Servo server's PlanningScene advertises the /get_planning_scene service, +# which other nodes can use as a source for information about the planning environment. +# NOTE: If a different node in your system is responsible for the "primary" planning scene instance (e.g. the MoveGroup node), +# then is_primary_planning_scene_monitor needs to be set to false. +is_primary_planning_scene_monitor: true + ## MoveIt properties move_group_name: panda_arm # Often 'manipulator' or 'arm' planning_frame: panda_link0 # The MoveIt planning frame. Often 'base_link' or 'world'