diff --git a/docker-compose.yaml b/docker-compose.yaml index a2e08320..84b18c74 100644 --- a/docker-compose.yaml +++ b/docker-compose.yaml @@ -1,14 +1,12 @@ # Docker Compose file for user overlays of the MoveIt Pro images. -version: "3.9" - services: # Sets common properties for other services. Should not be instantiated directly. base: # Extend the installed MoveIt Pro docker compose file. # Change this to match your environment, if MoveIt Pro was installed to a different location. extends: - file: ${HOME}/moveit_pro/docker-compose.yaml + file: /opt/moveit_pro/docker-compose.yaml service: base image: moveit-pro-overlay build: diff --git a/src/moveit_studio_ur_pstop_manager/package.xml b/src/moveit_studio_ur_pstop_manager/package.xml index 525faf5a..3252f948 100644 --- a/src/moveit_studio_ur_pstop_manager/package.xml +++ b/src/moveit_studio_ur_pstop_manager/package.xml @@ -2,7 +2,7 @@ moveit_studio_ur_pstop_manager - 4.0.1 + 5.0.0 Provides a node to monitor the protective stop state of the UR5, and reset protective stops when necessary. MoveIt Pro Maintainer 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_base_config/package.xml b/src/picknik_ur_base_config/package.xml index 627b9bec..b1b0269d 100644 --- a/src/picknik_ur_base_config/package.xml +++ b/src/picknik_ur_base_config/package.xml @@ -1,7 +1,7 @@ picknik_ur_base_config - 4.0.1 + 5.0.0 Base configuration package for Picknik's UR robot arms 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_gazebo_config/package.xml b/src/picknik_ur_gazebo_config/package.xml index 232a3bce..b04ed25f 100644 --- a/src/picknik_ur_gazebo_config/package.xml +++ b/src/picknik_ur_gazebo_config/package.xml @@ -1,7 +1,7 @@ picknik_ur_gazebo_config - 4.0.1 + 5.0.0 Site configuration package for the UR5e in PickNik's space station world simulated by Gazebo. diff --git a/src/picknik_ur_gazebo_scan_and_plan_config/package.xml b/src/picknik_ur_gazebo_scan_and_plan_config/package.xml index 3d2bdf21..735220bf 100644 --- a/src/picknik_ur_gazebo_scan_and_plan_config/package.xml +++ b/src/picknik_ur_gazebo_scan_and_plan_config/package.xml @@ -1,7 +1,7 @@ picknik_ur_gazebo_scan_and_plan_config - 4.0.1 + 5.0.0 Site configuration package for the UR5e simulated in Gazebo to show "scan and plan" applications. 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] diff --git a/src/picknik_ur_mock_hw_config/package.xml b/src/picknik_ur_mock_hw_config/package.xml index db552108..60ebd41d 100644 --- a/src/picknik_ur_mock_hw_config/package.xml +++ b/src/picknik_ur_mock_hw_config/package.xml @@ -1,7 +1,7 @@ picknik_ur_mock_hw_config - 4.0.1 + 5.0.0 Configuration package for a UR arm that can be simulated with mock hardware diff --git a/src/picknik_ur_site_config/package.xml b/src/picknik_ur_site_config/package.xml index 7aabcd23..eccb64d3 100644 --- a/src/picknik_ur_site_config/package.xml +++ b/src/picknik_ur_site_config/package.xml @@ -1,7 +1,7 @@ picknik_ur_site_config - 4.0.1 + 5.0.0 Site configuration package for a UR arm that can be simulated with mock hardware diff --git a/src/picknik_ur_studio_integration_testing/package.xml b/src/picknik_ur_studio_integration_testing/package.xml index 010dc11e..6e593730 100644 --- a/src/picknik_ur_studio_integration_testing/package.xml +++ b/src/picknik_ur_studio_integration_testing/package.xml @@ -2,7 +2,7 @@ picknik_ur_studio_integration_testing - 4.0.1 + 5.0.0 Integration tests for UR with MoveIt Pro. MoveIt Pro Maintainer