diff --git a/src/picknik_ur_base_config/config/moveit/ur_servo.yaml b/src/picknik_ur_base_config/config/moveit/ur_servo.yaml index 6c7f2f51..13d58e8a 100644 --- a/src/picknik_ur_base_config/config/moveit/ur_servo.yaml +++ b/src/picknik_ur_base_config/config/moveit/ur_servo.yaml @@ -39,6 +39,7 @@ acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_perio move_group_name: manipulator # Often 'manipulator' or 'arm' acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm' is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. +monitored_planning_scene_topic: /monitored_planning_scene ## Stopping behaviour incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command @@ -56,7 +57,8 @@ status_topic: ~/status # Publish status to this topic command_out_topic: /servo_controller/joint_trajectory # Publish outgoing commands here ## Collision checking for the entire robot body -check_collisions: true # Check collisions? +check_collisions: true # Check collisions? +check_octomap_collisions: false # Check collisions with octomap? collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. self_collision_proximity_threshold: 0.006 # Start decelerating when a self-collision is this far [m] scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/src/picknik_ur_gazebo_config/config/moveit/ur_servo.yaml b/src/picknik_ur_gazebo_config/config/moveit/ur_servo.yaml index 8e87eca1..c37cc5a0 100644 --- a/src/picknik_ur_gazebo_config/config/moveit/ur_servo.yaml +++ b/src/picknik_ur_gazebo_config/config/moveit/ur_servo.yaml @@ -39,6 +39,7 @@ acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_perio move_group_name: manipulator # Often 'manipulator' or 'arm' acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm' is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. +monitored_planning_scene_topic: /monitored_planning_scene ## Stopping behaviour incoming_command_timeout: 0.05 # Stop servoing if X seconds elapse without a new command @@ -57,6 +58,7 @@ command_out_topic: /robot_controllers/joint_trajectory # Publish outgoing comman ## Collision checking for the entire robot body check_collisions: true # Check collisions? +check_octomap_collisions: false # Check collisions with octomap? collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m] scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/src/picknik_ur_mock_hw_config/config/moveit/ur_servo.yaml b/src/picknik_ur_mock_hw_config/config/moveit/ur_servo.yaml index 45f8a4c0..49151897 100644 --- a/src/picknik_ur_mock_hw_config/config/moveit/ur_servo.yaml +++ b/src/picknik_ur_mock_hw_config/config/moveit/ur_servo.yaml @@ -37,6 +37,7 @@ acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_perio move_group_name: manipulator # Often 'manipulator' or 'arm' acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm' is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. +monitored_planning_scene_topic: /monitored_planning_scene ## Stopping behaviour incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command @@ -55,6 +56,7 @@ command_out_topic: /servo_controller/joint_trajectory # Publish outgoing command ## Collision checking for the entire robot body check_collisions: true # Check collisions? +check_octomap_collisions: false # Check collisions with octomap? collision_check_rate: 20.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. self_collision_proximity_threshold: 0.006 # Start decelerating when a self-collision is this far [m] scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m]