From 33e76dfeb41a08d4105133cc04e352cb041eee30 Mon Sep 17 00:00:00 2001 From: Michael Wrock Date: Wed, 7 Aug 2024 07:10:46 -0700 Subject: [PATCH] Changed ur types (#310) Signed-off-by: Paul Gesel Co-authored-by: Jeremy Bronson <109768477+jeremydbronson@users.noreply.github.com> Co-authored-by: Paul Gesel Co-authored-by: Abishalini Sivaraman Co-authored-by: David Yackzan --- .../config/config.yaml | 29 +- .../config/moveit/multi_arm_ur.srdf | 84 ---- .../description/multi_arm_ur.xacro | 69 ++- .../objectives/move_two_arms.xml | 26 +- .../waypoints/ur_waypoints.yaml | 228 +++++++++ .../CMakeLists.txt | 22 - .../LICENSE | 25 - .../README.md | 5 - .../config/cameras.yaml | 67 --- .../config/config.yaml | 207 -------- .../control/picknik_dual_ur.ros2_control.yaml | 241 ---------- .../config/moveit/dual_arm_joint_limits.yaml | 242 ---------- .../config/moveit/dual_arm_ur.srdf | 349 -------------- .../config/moveit/ompl_planning.yaml | 112 ----- .../config/moveit/pilz_cartesian_limits.yaml | 6 - .../config/moveit/stomp_planning.yaml | 22 - .../moveit/trac_ik_kinematics_distance.yaml | 12 - .../moveit/trac_ik_kinematics_speed.yaml | 12 - .../config/moveit/ur_servo.yaml | 60 --- .../description/camera_and_gripper.xacro | 135 ------ .../description/dual_arm_ur.xacro | 222 --------- .../space_station_blocks_world.sdf | 441 ------------------ .../launch/agent_bridge.launch.xml | 5 - .../launch/robot_drivers_to_persist.launch.py | 75 --- .../launch/sim/hardware_sim.launch.py | 352 -------------- .../robot_drivers_to_persist_sim.launch.py | 43 -- .../objectives/clear_snapshot.xml | 7 - .../objectives/close_left_gripper.xml | 8 - .../objectives/close_right_gripper.xml | 8 - .../objectives/interpolate_to_joint_state.xml | 20 - .../objectives/move_to_joint_state.xml | 20 - .../objectives/move_to_named_pose.xml | 13 - .../objectives/move_to_pose.xml | 21 - .../objectives/move_two_arms.xml | 30 -- .../objectives/open_left_gripper.xml | 9 - .../objectives/open_right_gripper.xml | 9 - .../objectives/pick_object.xml | 18 - .../objectives/pick_object_config.yaml | 11 - .../objectives/pick_object_left.yaml | 11 - .../objectives/reactivate_gripper.xml | 16 - .../objectives/request_teleoperation.xml | 53 --- .../objectives/reset_planning_scene.xml | 7 - .../objectives/take_snapshot.xml | 17 - .../objectives/teleoperate.xml | 7 - ..._trajectory_approval_if_user_available.xml | 11 - .../package.xml | 42 -- .../waypoints/waypoints.yaml | 241 ---------- 47 files changed, 270 insertions(+), 3400 deletions(-) delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/CMakeLists.txt delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/LICENSE delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/README.md delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/cameras.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/config.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/control/picknik_dual_ur.ros2_control.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_joint_limits.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_ur.srdf delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/ompl_planning.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/pilz_cartesian_limits.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/stomp_planning.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_distance.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_speed.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/config/moveit/ur_servo.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/description/camera_and_gripper.xacro delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/description/dual_arm_ur.xacro delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/description/simulation_worlds/space_station_blocks_world.sdf delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/launch/agent_bridge.launch.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/launch/robot_drivers_to_persist.launch.py delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/launch/sim/hardware_sim.launch.py delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/launch/sim/robot_drivers_to_persist_sim.launch.py delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/clear_snapshot.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/close_left_gripper.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/close_right_gripper.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/interpolate_to_joint_state.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_joint_state.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_named_pose.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_pose.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/move_two_arms.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/open_left_gripper.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/open_right_gripper.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_config.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_left.yaml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/reactivate_gripper.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/request_teleoperation.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/reset_planning_scene.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/take_snapshot.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/teleoperate.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/objectives/wait_for_trajectory_approval_if_user_available.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/package.xml delete mode 100644 src/picknik_ur_multi_arm_gazebo_config/waypoints/waypoints.yaml diff --git a/src/picknik_ur_multi_arm_config/config/config.yaml b/src/picknik_ur_multi_arm_config/config/config.yaml index 4eb77e35..c56f3a6d 100644 --- a/src/picknik_ur_multi_arm_config/config/config.yaml +++ b/src/picknik_ur_multi_arm_config/config/config.yaml @@ -1,11 +1,6 @@ # Baseline hardware configuration parameters for MoveIt Pro. # [Required] hardware: - # Used by the ur_description package to set kinematics and geometry for a specific robot type. - # You can change this to another UR model but you must update any configuration affected by the different arm size. - # UR models in the ur_description package are ur3, ur3e, ur5, ur5e, ur10, ur10e, and ur16e. - # [Required] - type: ur5e # Set simulated to false if you are using this as a configuration for real hardware. # This allows users to switch between mock and real hardware by changing a single parameter with config inheritance. @@ -26,9 +21,6 @@ hardware: robot_driver_persist_launch_file: package: "picknik_ur_base_config" path: "launch/robot_drivers_to_persist.launch.py" - hardware_launch_file: - package: "moveit_studio_agent" - path: "launch/blank.launch.py" # Specify any additional launch files for running the robot in simulation mode. # Used when hardware.simulated is True. @@ -36,9 +28,6 @@ hardware: simulated_robot_driver_persist_launch_file: package: "picknik_ur_base_config" path: "launch/sim/robot_drivers_to_persist_sim.launch.py" - simulated_hardware_launch_file: - package: "moveit_studio_agent" - path: "launch/blank.launch.py" # Parameters used to configure the robot description through XACRO. # A URDF and SRDF are both required. @@ -79,10 +68,7 @@ hardware: # Load visual_parameters.yaml from ur_description/config/ package: "ur_description" path: "config/ur5e/visual_parameters.yaml" - # Set advanced camera settings to improve point cloud accuracy - json_file_path: - package: "picknik_ur_base_config" - path: "config/realsense_config_high_accuracy.json" + # Sets ROS global params for launch. # [Optional] @@ -138,13 +124,6 @@ moveit_params: allowed_goal_duration_margin: 5.0 allowed_start_tolerance: 0.01 -# Additional configurable parameters for the MoveIt Pro user interface. -# [Required] -ui_params: - # By default, MoveIt Pro uses a frame called "grasp_link" for tool grasp pose rendering - # and planning. - # [Required] - servo_endpoint_frame_id: "first_grasp_link" # Configuration for launching ros2_control processes. # [Required, if using ros2_control] @@ -182,12 +161,6 @@ ros2_control: # [Optional, default=[]] controller_shared_topics: [] -# Octomap manager configuration parameters -octomap_manager: - # Input point cloud topic name. The *output* point cloud topic published by - # the Octomap manager node is defined in sensors_3d.yaml. - input_point_cloud_topic: "/wrist_mounted_camera/depth/color/points" - # Configuration for loading behaviors and objectives. # [Required] objectives: diff --git a/src/picknik_ur_multi_arm_config/config/moveit/multi_arm_ur.srdf b/src/picknik_ur_multi_arm_config/config/moveit/multi_arm_ur.srdf index 44e58209..b306e8a3 100644 --- a/src/picknik_ur_multi_arm_config/config/moveit/multi_arm_ur.srdf +++ b/src/picknik_ur_multi_arm_config/config/moveit/multi_arm_ur.srdf @@ -182,27 +182,6 @@ - - - - - - - - - - - - - - - - - - - - - @@ -331,27 +310,6 @@ - - - - - - - - - - - - - - - - - - - - - @@ -480,27 +438,6 @@ - - - - - - - - - - - - - - - - - - - - - @@ -629,27 +566,6 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_config/description/multi_arm_ur.xacro b/src/picknik_ur_multi_arm_config/description/multi_arm_ur.xacro index b6c6294e..18b02d84 100644 --- a/src/picknik_ur_multi_arm_config/description/multi_arm_ur.xacro +++ b/src/picknik_ur_multi_arm_config/description/multi_arm_ur.xacro @@ -23,6 +23,23 @@ + + + + + + + + + + + + + + + + + @@ -38,17 +55,16 @@ - - - - - - - - - - - - - - - - - - - - - + - + - - - - - - - - - - - - - - - - + + + + + + diff --git a/src/picknik_ur_multi_arm_config/waypoints/ur_waypoints.yaml b/src/picknik_ur_multi_arm_config/waypoints/ur_waypoints.yaml index 7b31e104..f7a0bb55 100644 --- a/src/picknik_ur_multi_arm_config/waypoints/ur_waypoints.yaml +++ b/src/picknik_ur_multi_arm_config/waypoints/ur_waypoints.yaml @@ -1,3 +1,92 @@ +- description: '' + favorite: false + joint_group_names: + - first_manipulator + - fourth_gripper + - fourth_manipulator + - gripper + - multi_arm_manipulator + - second_gripper + - second_manipulator + - third_gripper + - third_manipulator + joint_state: + effort: [] + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + name: + - first_shoulder_pan_joint + - first_shoulder_lift_joint + - first_elbow_joint + - first_wrist_1_joint + - first_wrist_2_joint + - first_wrist_3_joint + - fourth_robotiq_85_left_knuckle_joint + - fourth_shoulder_pan_joint + - fourth_shoulder_lift_joint + - fourth_elbow_joint + - fourth_wrist_1_joint + - fourth_wrist_2_joint + - fourth_wrist_3_joint + - first_robotiq_85_left_knuckle_joint + - second_shoulder_pan_joint + - second_shoulder_lift_joint + - second_elbow_joint + - second_wrist_1_joint + - second_wrist_2_joint + - second_wrist_3_joint + - third_shoulder_pan_joint + - third_shoulder_lift_joint + - third_elbow_joint + - third_wrist_1_joint + - third_wrist_2_joint + - third_wrist_3_joint + - second_robotiq_85_left_knuckle_joint + - third_robotiq_85_left_knuckle_joint + position: + - 3.027358056711766 + - -2.027755258226139 + - 0.8567979964335799 + - -1.199517195007012 + - -1.4851165271515387 + - 0.00019073125240392984 + - 0.7929 + - -3.141561346270125 + - -1.71359599286716 + - 0.4855188646456952 + - -0.6283185307179586 + - -1.5993562600093492 + - 3.672383190132678e-05 + - 0.7929 + - 3.055875023715748 + - -1.770715859296065 + - 0.7711181967902214 + - -0.3712791317878848 + - -1.5707963267948966 + - 0.00013646876746788622 + - -3.1415909278466643 + - -1.71359599286716 + - 0.48551886464569516 + - -0.7500245148129295 + - -1.513676460365991 + - -5.523976171389222e-05 + - 0.7929 + - 0.7929 + velocity: [] + multi_dof_joint_state: + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + joint_names: [] + transforms: [] + twist: [] + wrench: [] + name: Flip - description: '' favorite: true joint_group_names: @@ -37,6 +126,16 @@ - 1.6699864011902827 - -9.210125892423094e-05 velocity: [] + multi_dof_joint_state: + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + joint_names: [] + transforms: [] + twist: [] + wrench: [] name: Two Arms Down - description: Home Flipped favorite: true @@ -104,7 +203,106 @@ - -1.669 - 3.141 velocity: [] + multi_dof_joint_state: + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + joint_names: [] + transforms: [] + twist: [] + wrench: [] name: Home Flipped +- description: '' + favorite: true + joint_group_names: + - first_manipulator + - fourth_gripper + - fourth_manipulator + - gripper + - multi_arm_manipulator + - second_gripper + - second_manipulator + - third_gripper + - third_manipulator + joint_state: + effort: [] + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + name: + - first_shoulder_pan_joint + - first_shoulder_lift_joint + - first_elbow_joint + - first_wrist_1_joint + - first_wrist_2_joint + - first_wrist_3_joint + - fourth_robotiq_85_left_knuckle_joint + - fourth_shoulder_pan_joint + - fourth_shoulder_lift_joint + - fourth_elbow_joint + - fourth_wrist_1_joint + - fourth_wrist_2_joint + - fourth_wrist_3_joint + - first_robotiq_85_left_knuckle_joint + - second_shoulder_pan_joint + - second_shoulder_lift_joint + - second_elbow_joint + - second_wrist_1_joint + - second_wrist_2_joint + - second_wrist_3_joint + - third_shoulder_pan_joint + - third_shoulder_lift_joint + - third_elbow_joint + - third_wrist_1_joint + - third_wrist_2_joint + - third_wrist_3_joint + - second_robotiq_85_left_knuckle_joint + - third_robotiq_85_left_knuckle_joint + position: + - 3.027352920731983 + - -1.0129336116452234 + - -1.7989371590030379 + - -0.7500431305404287 + - 1.6689824679556302 + - 9.53144878614694e-05 + - 0.7929 + - -3.141592653589793 + - -1.0129416442132089 + - -1.7130895491734148 + - -0.7499239977449179 + - 1.6689872079757508 + - 8.899450297467411e-05 + - 0.7929 + - 3.0559128539464346 + - -1.0130466124989557 + - -1.712902314238716 + - -0.7499221115582158 + - 1.6690666370701976 + - 4.438869529403747e-05 + - -3.141592653589793 + - -1.3137569278648227 + - -0.9139178628624852 + - -0.7499328942831606 + - 1.6689088345160707 + - 1.0323978960514069e-05 + - 0.7929 + - 0.7929 + velocity: [] + multi_dof_joint_state: + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + joint_names: [] + transforms: [] + twist: [] + wrench: [] + name: Back - description: Arms down favorite: true joint_group_names: @@ -171,6 +369,16 @@ - 1.6699516917224972 - 0 velocity: [] + multi_dof_joint_state: + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + joint_names: [] + transforms: [] + twist: [] + wrench: [] name: Arms Down - description: Home twisted favorite: true @@ -238,6 +446,16 @@ - 1.669 - 0 velocity: [] + multi_dof_joint_state: + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + joint_names: [] + transforms: [] + twist: [] + wrench: [] name: Home Twisted - description: Home favorite: true @@ -305,4 +523,14 @@ - 1.669 - 0 velocity: [] + multi_dof_joint_state: + header: + frame_id: '' + stamp: + nanosec: 0 + sec: 0 + joint_names: [] + transforms: [] + twist: [] + wrench: [] name: Home diff --git a/src/picknik_ur_multi_arm_gazebo_config/CMakeLists.txt b/src/picknik_ur_multi_arm_gazebo_config/CMakeLists.txt deleted file mode 100644 index fe5914de..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -cmake_minimum_required(VERSION 3.22) -project(picknik_ur_multi_arm_gazebo_config) - -find_package(ament_cmake REQUIRED) - -install( - DIRECTORY - config - description - launch - objectives - waypoints - DESTINATION - share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/src/picknik_ur_multi_arm_gazebo_config/LICENSE b/src/picknik_ur_multi_arm_gazebo_config/LICENSE deleted file mode 100644 index 574ef079..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - * Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. diff --git a/src/picknik_ur_multi_arm_gazebo_config/README.md b/src/picknik_ur_multi_arm_gazebo_config/README.md deleted file mode 100644 index 71574513..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# picknik_multi_ur_gazebo_config - -A MoveIt Pro example configuration package for using multiple UR5e arms using gazebo ignition. - -For further documentation see: [MoveIt Pro Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/cameras.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/cameras.yaml deleted file mode 100644 index 565f04ec..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/cameras.yaml +++ /dev/null @@ -1,67 +0,0 @@ -# Placeholders for camera configuration. -# Cameras are not a requirement for running MoveIt Pro, but this is provided as an -# example for plugging in Realsense D415 camera topics to the application. - -- scene_camera: - camera_name: "scene_camera" - type: "sim" - use: True - serial_no: "0" - device_type: "D415" - framerate: 6 - image_width: 640 - image_height: 480 - - # information about the topics the camera publishes the raw image and info - rgb_info: "/scene_camera/color/camera_info" - rgb_image: "/scene_camera/color/image_raw" - - registered_rgb_depth_pair: - depth_info: "/scene_camera/color/camera_info" - depth_image: "/scene_camera/depth/image_rect_raw" - registered_info: "/scene_camera/depth_registered/camera_info" - registered_image: "/scene_camera/depth_registered/image_rect_raw" - -- left_wrist_mounted_camera: - camera_name: "left_wrist_mounted_camera" - type: "sim" - use: True - serial_no: "0" - device_type: "D415" - framerate: 6 - image_width: 640 - image_height: 480 - enable_pointcloud: True - - # information about the topics the camera publishes the raw image and info - rgb_info: "/left_wrist_mounted_camera/color/camera_info" - rgb_image: "/left_wrist_mounted_camera/color/image_raw" - - # By adding registered_rgb_depth_pair, This camera can be used for "Set Transform From Click" - registered_rgb_depth_pair: - depth_info: "/left_wrist_mounted_camera/color/camera_info" - depth_image: "/left_wrist_mounted_camera/depth/image_rect_raw" - registered_info: "/left_wrist_mounted_camera/depth_registered/camera_info" - registered_image: "/left_wrist_mounted_camera/depth_registered/image_rect" - -- right_wrist_mounted_camera: - camera_name: "right_wrist_mounted_camera" - type: "sim" - use: True - serial_no: "0" - device_type: "D415" - framerate: 6 - image_width: 640 - image_height: 480 - enable_pointcloud: True - - # information about the topics the camera publishes the raw image and info - rgb_info: "/right_wrist_mounted_camera/color/camera_info" - rgb_image: "/right_wrist_mounted_camera/color/image_raw" - - # By adding registered_rgb_depth_pair, This camera can be used for "Set Transform From Click" - registered_rgb_depth_pair: - depth_info: "/right_wrist_mounted_camera/color/camera_info" - depth_image: "/right_wrist_mounted_camera/depth/image_rect_raw" - registered_info: "/right_wrist_mounted_camera/depth_registered/camera_info" - registered_image: "/right_wrist_mounted_camera/depth_registered/image_rect" diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/config.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/config.yaml deleted file mode 100644 index 6702f230..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/config.yaml +++ /dev/null @@ -1,207 +0,0 @@ -# -# This contains information for a unique instance of a robot. -# - -# Optional parameters that can be read in your launch files for specific functionality -optional_feature_params: - gazebo_world_name: "space_station_blocks_world.sdf" - gazebo_gui: False - gazebo_verbose: True - -hardware: - # Used by the ur_description package to set kinematics and geometry for a specific robot type. - # You can change this to another UR model but you must update any configuration affected by the different arm size. - # UR models in the ur_description package are ur3, ur3e, ur5, ur5e, ur10, ur10e, and ur16e. - type: "ur5e" - - # This is the only option for this site_config - simulated: True - - # Gazebo starts its own controller manager through the ros2_control plugin, so set this to False - launch_control_node: False - - # If the MoveIt Pro Agent should launch the robot state publisher - # This should be false if you are launching the robot state publisher as part of drivers. - # [Optional, default=True] - launch_robot_state_publisher: True - - # If the MoveIt Pro Agent should launch cameras when simulated. - launch_cameras_when_simulated: True - - # Specify any additional launch files for running the robot in simulation mode. - # Used when hardware.simulated is True. - # [Optional, defaults to a blank launch file if not specified] - - - simulated_hardware_launch_file: - package: "picknik_ur_multi_arm_gazebo_config" - path: "launch/sim/hardware_sim.launch.py" - - # Configuration details for cameras and scene planning. - # [Required] - camera_config_file: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/cameras.yaml" - - # Parameters used to configure the robot description through XACRO. - # A URDF and SRDF are both required. - # [Required] - robot_description: - urdf: - package: "picknik_ur_multi_arm_gazebo_config" - path: "description/dual_arm_ur.xacro" - srdf: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/moveit/dual_arm_ur.srdf" - # Specify any additional parameters required for the URDF. - # Many of these are specific to the UR descriptions packages, and can be customized as needed. - # [Optional] - urdf_params: - - name: "dual_arm_ur" - - prefix: "" - - use_fake_hardware: "false" - - gripper_name: "robotiq_85" - - use_pinch_links: "true" - - simulation: "gazebo" - - fake_sensor_commands: "false" - - headless_mode: "true" - - robot_ip: "0.0.0.0" - - joint_limits_parameters_file: - package: "picknik_ur_base_config" - path: "config/moveit/joint_limits.yaml" - # The following files are loaded based on the ur_description package layout. - # To use parameters from a different package, place them in a config/ROBOT_NAME/ directory, - # replace ROBOT_NAME with the value used for hardware.type in this file. - - kinematics_parameters_file: - # Load default_kinematics.yaml from ur_description/config/ - package: "ur_description" - path: "config/ur5e/default_kinematics.yaml" - - physical_parameters_file: - # Load physical_parameters.yaml from ur_description/config/ - package: "ur_description" - path: "config/ur5e/physical_parameters.yaml" - - visual_parameters_file: - # Load visual_parameters.yaml from ur_description/config/ - package: "ur_description" - path: "config/ur5e/visual_parameters.yaml" - -# Sets ROS global params for launch. -# [Optional] -ros_global_params: - # Whether or not to use simulated time. - # [Optional, default=False] - use_sim_time: True - -# Configuration files for MoveIt. -# For more information, refer to https://moveit.picknik.ai/main/doc/how_to_guides/moveit_configuration/moveit_configuration_tutorial.html -# [Required] -moveit_params: - # Used by the Waypoint Manager to save joint states from this joint group. - joint_group_name: "manipulator_right" - - ompl_planning: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/moveit/ompl_planning.yaml" - pilz_planning: - package: "picknik_ur_base_config" - path: "config/moveit/pilz_industrial_motion_planner_planning.yaml" - stomp_planning: - package: "picknik_ur_base_config" - path: "config/moveit/stomp_planning.yaml" - kinematics: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/moveit/trac_ik_kinematics_distance.yaml" - servo: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/moveit/ur_servo.yaml" - sensors_3d: - package: "picknik_ur_base_config" - path: "config/moveit/sensors_3d.yaml" - servo_kinematics: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/moveit/trac_ik_kinematics_speed.yaml" - joint_limits: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/moveit/dual_arm_joint_limits.yaml" - pilz_cartesian_limits: - package: "picknik_ur_base_config" - path: "config/moveit/pilz_cartesian_limits.yaml" - - publish: - planning_scene: True - geometry_updates: True - state_updates: True - transforms_updates: True - - trajectory_execution: - manage_controllers: True - allowed_execution_duration_scaling: 2.0 - allowed_goal_duration_margin: 5.0 - allowed_start_tolerance: 0.01 - -# Additional configurable parameters for the MoveIt Pro user interface. -# [Required] -ui_params: - # By default, MoveIt Pro uses a frame called "grasp_link" for tool grasp pose rendering - # and planning. - # [Required] - servo_endpoint_frame_id: "right_grasp_link" - - -# This configures what controllers gets run at startup -ros2_control: - config: - package: "picknik_ur_multi_arm_gazebo_config" - path: "config/control/picknik_dual_ur.ros2_control.yaml" - # MoveIt Pro will load and activate these controllers at start up to ensure they are available. - # If not specified, it is up to the user to ensure the appropriate controllers are active and available - # for running the application. - # [Optional, default=[]] - controllers_active_at_startup: - - "joint_state_broadcaster" - - "servo_controller" - - "left_robotiq_gripper_controller" - - "right_robotiq_gripper_controller" - # Load but do not start these controllers so they can be activated later if needed. - # [Optional, default=[]] - controllers_inactive_at_startup: - - "left_joint_trajectory_controller" - - "right_joint_trajectory_controller" - - "dual_arm_joint_trajectory_controller" - # Any controllers here will not be spawned by MoveIt Pro. - # [Optional, default=[]] - controllers_not_managed: [] - # Optionally configure remapping rules to let multiple controllers receive commands on the same topic. - # [Optional, default=[]] - controller_shared_topics: [] - -# Octomap manager configuration parameters -octomap_manager: - # Input point cloud topic name. The *output* point cloud topic published by - # the Octomap manager node is defined in sensors_3d.yaml. - input_point_cloud_topic: "/left_wrist_mounted_camera/depth/color/points" - -# Configuration for loading behaviors and objectives. -# [Required] -objectives: - # List of plugins for loading custom behaviors. - # [Required] - behavior_loader_plugins: - # This plugin will load the core MoveIt Pro behaviors. - # Add additional plugin loaders as needed. - core: - - "moveit_studio::behaviors::CoreBehaviorsLoader" - - "moveit_studio::behaviors::MTCCoreBehaviorsLoader" - - "moveit_studio::behaviors::ServoBehaviorsLoader" - - "moveit_studio::behaviors::VisionBehaviorsLoader" - # Specify source folder for objectives - # [Required] - objective_library_paths: - core: - package_name: "picknik_ur_multi_arm_gazebo_config" - relative_path: "objectives" - # Specify the location of the saved waypoints file. - # [Required] - waypoints_file: - package_name: "picknik_ur_multi_arm_gazebo_config" - relative_path: "waypoints/waypoints.yaml" diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/control/picknik_dual_ur.ros2_control.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/control/picknik_dual_ur.ros2_control.yaml deleted file mode 100644 index 5675518c..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/control/picknik_dual_ur.ros2_control.yaml +++ /dev/null @@ -1,241 +0,0 @@ -controller_manager: - ros__parameters: - update_rate: 200 # Hz - joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - left_joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - right_joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - dual_arm_joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - left_robotiq_gripper_controller: - type: position_controllers/GripperActionController - right_robotiq_gripper_controller: - type: position_controllers/GripperActionController - servo_controller: - type: joint_trajectory_controller/JointTrajectoryController - -left_joint_trajectory_controller: - ros__parameters: - joints: - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - left_shoulder_pan_joint: - goal: 0.05 - left_shoulder_lift_joint: - goal: 0.05 - left_elbow_joint: - goal: 0.05 - left_wrist_1_joint: - goal: 0.05 - left_wrist_2_joint: - goal: 0.05 - left_wrist_3_joint: - goal: 0.05 - -right_joint_trajectory_controller: - ros__parameters: - joints: - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - right_shoulder_pan_joint: - goal: 0.05 - right_shoulder_lift_joint: - goal: 0.05 - right_elbow_joint: - goal: 0.05 - right_wrist_1_joint: - goal: 0.05 - right_wrist_2_joint: - goal: 0.05 - right_wrist_3_joint: - goal: 0.05 - -dual_arm_joint_trajectory_controller: - ros__parameters: - joints: - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: true - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - left_shoulder_pan_joint: - goal: 0.05 - left_shoulder_lift_joint: - goal: 0.05 - left_elbow_joint: - goal: 0.05 - left_wrist_1_joint: - goal: 0.05 - left_wrist_2_joint: - goal: 0.05 - left_wrist_3_joint: - goal: 0.05 - right_shoulder_pan_joint: - goal: 0.05 - right_shoulder_lift_joint: - goal: 0.05 - right_elbow_joint: - goal: 0.05 - right_wrist_1_joint: - goal: 0.05 - right_wrist_2_joint: - goal: 0.05 - right_wrist_3_joint: - goal: 0.05 - -servo_controller: - ros__parameters: - joints: - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - command_interfaces: - - position - state_interfaces: - - position - - velocity - command_joints: - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - state_publish_rate: 100.0 - action_monitor_rate: 20.0 - allow_partial_joints_goal: false - constraints: - stopped_velocity_tolerance: 0.0 - goal_time: 0.0 - right_shoulder_pan_joint: - goal: 0.05 - right_shoulder_lift_joint: - goal: 0.05 - right_elbow_joint: - goal: 0.05 - right_wrist_1_joint: - goal: 0.05 - right_wrist_2_joint: - goal: 0.05 - right_wrist_3_joint: - goal: 0.05 - left_shoulder_pan_joint: - goal: 0.05 - left_shoulder_lift_joint: - goal: 0.05 - left_elbow_joint: - goal: 0.05 - left_wrist_1_joint: - goal: 0.05 - left_wrist_2_joint: - goal: 0.05 - left_wrist_3_joint: - goal: 0.05 - -left_robotiq_gripper_controller: - ros__parameters: - default: true - joint: left_robotiq_85_left_knuckle_joint - allow_stalling: true - stall_velocity_threshold: 0.075 - stall_timeout: 0.2 - -right_robotiq_gripper_controller: - ros__parameters: - default: true - joint: right_robotiq_85_left_knuckle_joint - allow_stalling: true - stall_velocity_threshold: 0.075 - stall_timeout: 0.2 diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_joint_limits.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_joint_limits.yaml deleted file mode 100644 index 6c453078..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_joint_limits.yaml +++ /dev/null @@ -1,242 +0,0 @@ -# Joints limits -# -# Sources: -# -# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 -# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_User_Manual_en_Global.pdf -# - Support > Articles > UR articles > Max. joint torques -# https://www.universal-robots.com/articles/ur-articles/max-joint-torques -# retrieved: 2020-06-16, last modified: 2020-06-09 -# -# NOTE: Acceleration limits are not publicly available so we have picked a reasonable upper limit -joint_limits: - left_shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - left_shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - left_elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - left_wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - left_wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - left_wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - left_robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 - - - right_shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - right_shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - right_elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - right_wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - right_wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - right_wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - right_robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 - -# UR robots use hard coded values that ignore prefixes - - shoulder_pan_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - shoulder_lift_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - max_position: !degrees 90.0 - max_velocity: !degrees 30.0 - min_position: !degrees -270.0 - elbow_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 150.0 - # we artificially limit this joint to half its actual joint position limit - # to avoid (MoveIt/OMPL) planning problems, as due to the physical - # construction of the robot, it's impossible to rotate the 'elbow_joint' - # over more than approx +- 1 pi (the shoulder lift joint gets in the way). - # - # This leads to planning problems as the search space will be divided into - # two sections, with no connections from one to the other. - # - # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for - # more information. - max_position: !degrees 180.0 - max_velocity: !degrees 30.0 - min_position: !degrees -180.0 - wrist_1_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_2_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 180.0 - max_velocity: !degrees 60.0 - min_position: !degrees -180.0 - wrist_3_joint: - has_acceleration_limits: true - has_effort_limits: true - has_position_limits: true - has_velocity_limits: true - max_acceleration: !degrees 30.0 - max_effort: 28.0 - max_position: !degrees 360.0 - max_velocity: !degrees 60.0 - min_position: !degrees -360.0 - robotiq_85_left_knuckle_joint: - has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 1.0 diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_ur.srdf b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_ur.srdf deleted file mode 100644 index c6732b4d..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/dual_arm_ur.srdf +++ /dev/null @@ -1,349 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/ompl_planning.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/ompl_planning.yaml deleted file mode 100644 index f7ec7771..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/ompl_planning.yaml +++ /dev/null @@ -1,112 +0,0 @@ -planning_plugins: - - ompl_interface/OMPLPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - - default_planning_response_adapters/DisplayMotionPath - -planner_configs: - APSConfigDefault: - type: geometric::AnytimePathShortening - shortcut: 1 # Attempt to shortcut all new solution paths - hybridize: 1 # Compute hybrid solution trajectories - max_hybrid_paths: 32 # Number of hybrid paths generated per iteration - num_planners: 16 # The number of default planners to use for planning - planners: "RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - RRTkConfigDefault: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnectkConfigDefault: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstarkConfigDefault: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRTkConfigDefault: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup() - PRMkConfigDefault: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstarkConfigDefault: - type: geometric::PRMstar - -manipulator_left: - default_planner_config: RRTConnectkConfigDefault - planner_configs: - - APSConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - enforce_constrained_state_space: true - longest_valid_segment_fraction: 0.01 -gripper_left: - planner_configs: - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault -gripper: - planner_configs: - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - -manipulator_right: - default_planner_config: RRTConnectkConfigDefault - planner_configs: - - APSConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - enforce_constrained_state_space: true - longest_valid_segment_fraction: 0.01 -gripper_right: - planner_configs: - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - -dual_arm_manipulator: - default_planner_config: RRTConnectkConfigDefault - planner_configs: - - APSConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - enforce_constrained_state_space: true - longest_valid_segment_fraction: 0.01 diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/pilz_cartesian_limits.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/pilz_cartesian_limits.yaml deleted file mode 100644 index 1633938e..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/pilz_cartesian_limits.yaml +++ /dev/null @@ -1,6 +0,0 @@ -# Cartesian limits for the Pilz planner -cartesian_limits: - max_trans_vel: 0.1 - max_trans_acc: 0.1 - max_trans_dec: -0.1 - max_rot_vel: 0.1 diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/stomp_planning.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/stomp_planning.yaml deleted file mode 100644 index dc6fd444..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/stomp_planning.yaml +++ /dev/null @@ -1,22 +0,0 @@ -planning_plugins: - - stomp_moveit/StompPlanner -# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline. -request_adapters: - - default_planning_request_adapters/ResolveConstraintFrames - - default_planning_request_adapters/ValidateWorkspaceBounds - - default_planning_request_adapters/CheckStartStateBounds - - default_planning_request_adapters/CheckStartStateCollision -response_adapters: - - default_planning_response_adapters/AddTimeOptimalParameterization - - default_planning_response_adapters/ValidateSolution - - default_planning_response_adapters/DisplayMotionPath - -stomp_moveit: - num_timesteps: 60 - num_iterations: 40 - num_iterations_after_valid: 0 - num_rollouts: 30 - max_rollouts: 30 - exponentiated_cost_sensitivity: 0.8 - control_cost_weight: 0.1 - delta_t: 0.1 diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_distance.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_distance.yaml deleted file mode 100644 index afdc636c..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_distance.yaml +++ /dev/null @@ -1,12 +0,0 @@ -manipulator_left: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Distance" -manipulator_right: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Distance" diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_speed.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_speed.yaml deleted file mode 100644 index fe311e4a..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/trac_ik_kinematics_speed.yaml +++ /dev/null @@ -1,12 +0,0 @@ -manipulator_left: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Speed" -manipulator_right: - kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - epsilon: 0.0001 - solve_type: "Speed" diff --git a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/ur_servo.yaml b/src/picknik_ur_multi_arm_gazebo_config/config/moveit/ur_servo.yaml deleted file mode 100644 index b26594ad..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/config/moveit/ur_servo.yaml +++ /dev/null @@ -1,60 +0,0 @@ -############################################### -# Modify all parameters related to servoing here -############################################### - -# Enable dynamic parameter updates -enable_parameter_update: true - -## Properties of incoming commands -command_in_type: "unitless" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s -scale: - # Scale parameters are only used if command_in_type=="unitless" - linear: 2.0 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands. - rotational: 3.0 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands. - # Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic. - joint: 2.0 - -# Default to driving the arm at 50% maximum speed. -override_velocity_scaling_factor: 0.5 - -## Properties of outgoing commands -publish_period: 0.002 # 1/Nominal publish rate [seconds] - -# What type of topic does your robot driver expect? -# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory -command_out_type: trajectory_msgs/JointTrajectory - -# What to publish? Can save some bandwidth as most robots only require positions or velocities -publish_joint_positions: true -publish_joint_velocities: false -publish_joint_accelerations: false - -## Plugins for smoothing outgoing commands -use_smoothing: true -smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin" -low_pass_filter_coeff: 1.5 # Larger --> trust the filtered data more, trust the measurements less. - -## MoveIt properties -move_group_name: manipulator_right # 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. - -## Stopping behaviour -incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command - -## Configure handling of singularities and joint limits -lower_singularity_threshold: 30.0 # Start decelerating when the condition number hits this (close to singularity) -hard_stop_singularity_threshold: 50.0 # Stop when the condition number hits this -joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians]. If moving quickly, make this larger. - -## Topic names -cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands -joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands -joint_topic: /joint_states -status_topic: ~/status # Publish status to this topic -command_out_topic: /servo_controller/commands # Publish outgoing commands here - -## Collision checking for the entire robot body -check_collisions: true # Check collisions? -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_multi_arm_gazebo_config/description/camera_and_gripper.xacro b/src/picknik_ur_multi_arm_gazebo_config/description/camera_and_gripper.xacro deleted file mode 100644 index 2dd4becc..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/description/camera_and_gripper.xacro +++ /dev/null @@ -1,135 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 1.047 - - 640 - 480 - RGB_INT8 - - - 0.1 - 5 - - - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 -
0.5 0.5
-
- - - 554.25469 - 554.25469 - 320.5 - 240.5 - 0 - - - - 554.25469 - 554.25469 - 320.5 - 240.5 - 0 - 0 - - - - gaussian - 0 - 0.00 - - - - 0.25 - 5 - - - ${prefix_}wrist_mounted_camera_color_optical_frame -
- ${prefix_}wrist_mounted_camera_color_frame - 1 - 6 - false - ${prefix_}wrist_mounted_camera - false -
-
- - - - - - - - - - - - - - - - - -
-
diff --git a/src/picknik_ur_multi_arm_gazebo_config/description/dual_arm_ur.xacro b/src/picknik_ur_multi_arm_gazebo_config/description/dual_arm_ur.xacro deleted file mode 100644 index 10328d78..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/description/dual_arm_ur.xacro +++ /dev/null @@ -1,222 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 1 - 50 - 0 - left_tcp_fts_sensor/ft_data - 0 0 0 0 0 0 - - child - parent_to_child - - - - 0 - 0 - - - - - 0 - 0 - - - - - 0 - 0 - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 0 - 0 - - - - - - - - - - - $(find picknik_ur_multi_arm_gazebo_config)/config/control/picknik_dual_ur.ros2_control.yaml - - /left_servo_controller/commands:=/left_robot_controllers/commands - /left_servo_controller/joint_trajectory:=/left_robot_controllers/joint_trajectory - /right_servo_controller/commands:=/right_robot_controllers/commands - /right_servo_controller/joint_trajectory:=/right_robot_controllers/joint_trajectory - /servo_controller/commands:=/robot_controllers/commands - /servo_controller/joint_trajectory:=/robot_controllers/joint_trajectory - - - - - - - ${gazebo_renderer} - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/description/simulation_worlds/space_station_blocks_world.sdf b/src/picknik_ur_multi_arm_gazebo_config/description/simulation_worlds/space_station_blocks_world.sdf deleted file mode 100644 index 5912c6a1..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/description/simulation_worlds/space_station_blocks_world.sdf +++ /dev/null @@ -1,441 +0,0 @@ - - - - - 0.005 - 0.005 - 1.0 - - - - - - - - - - - - - - - 0.0 0.0 0.0 1.0 - 0 - - - - false - 0 0 100 0 0 0 - 0.6 0.6 0.6 1 - 0.2 0.2 0.2 1 - - 1000 - 0.9 - 0.01 - 0.001 - - -0.5 0.5 -1.0 - - - false - 0 0 100 0 0 0 - 0.8 0.8 0.8 1 - 0.2 0.2 0.2 1 - - 1000 - 0.9 - 0.01 - 0.001 - - -0.5 -0.5 -1.0 - - - false - 0 0 -100 0 0 0 - 0.5 0.5 0.5 1 - 0.5 0.5 0.5 1 - - 1000 - 0.9 - 0.01 - 0.001 - - 0.0 0.0 1.0 - - - false - 100 75 1.5 0 0 0 - 0.4 0.4 0.4 1 - 0.4 0.4 0.4 1 - - 1000 - 0.9 - 0.01 - 0.001 - - -1.0 -0.75 0.0 - - - false - 100 -75 1.5 0 0 0 - 0.4 0.4 0.4 - 0.4 0.4 0.4 1 - - 1000 - 0.9 - 0.01 - 0.001 - - -1.0 0.75 0.0 - - - - true - - - - - 0 0 1 - 100 100 - - - - - - - 0 0 1 - 100 100 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - - - - true - - - - - package://picknik_accessories/descriptions/furniture/space_station/space_booth.dae - - - - - - - package://picknik_accessories/descriptions/furniture/space_station/space_booth.dae - - - - -1 0 0 0 0 0 - - false - - - - - true - 0 0 1 0 0 0 - - - - - 1.5 1.0 0.05 - - - - - - 0.6 - 0.6 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.001 - - - - - - - - - 1.5 1.0 0.05 - - - - 0.93 0.89 0.75 1.0 - 0.93 0.89 0.75 1.0 - - - - - - - - -0.6 -0.3 1.1 0 0 0 - - - - 0.0001875 - 0 - 0 - 0.0001875 - 0 - 0.0001875 - - 0.2 - - - - - 0.05 0.05 0.05 - - - - - - 1000000.0 - 1000000.0 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.002 - 0 - - - - - - - - - 0.05 0.05 0.05 - - - - 1 0 0 1 - 1 0 0 1 - 1 0 0 1 - - - - - - - -0.6 0.0 1.1 0 0 0 - - - - 0.0001875 - 0 - 0 - 0.0001875 - 0 - 0.0001875 - - 0.2 - - - - - 0.05 0.05 0.05 - - - - - - 1000000.0 - 1000000.0 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.002 - 0 - - - - - - - - - 0.05 0.05 0.05 - - - - 0 1 0 1 - 0 1 0 1 - 0 1 0 1 - - - - - - - -0.6 0.3 1.1 0 0 0 - - - - 0.0001875 - 0 - 0 - 0.0001875 - 0 - 0.0001875 - - 0.2 - - - - - 0.05 0.05 0.05 - - - - - - 1000000.0 - 1000000.0 - - - - - 1e+5 - 1 - 0 - 0.2 - 0.002 - 0 - - - - - - - - - 0.05 0.05 0.05 - - - - 0 0 1 1 - 0 0 1 1 - 0 0 1 1 - - - - - - - - -0.5 -0.3 1.03 0 0 0 - - - - - 1 1 1 - package://picknik_ur_gazebo_config/description/apriltags/tag36_11_00001.dae - - - - - - 0.0001 - 0 - 0 - 0.0001 - 0 - 0.0001 - - 0.01 - - - 1 - - - - -0.5 0.0 1.03 0 0 0 - - - - - 1 1 1 - package://picknik_ur_gazebo_config/description/apriltags/tag36_11_00002.dae - - - - - - 0.0001 - 0 - 0 - 0.0001 - 0 - 0.0001 - - 0.01 - - - 1 - - - - -0.5 0.3 1.03 0 0 0 - - - - - 1 1 1 - package://picknik_ur_gazebo_config/description/apriltags/tag36_11_00003.dae - - - - - - 0.0001 - 0 - 0 - 0.0001 - 0 - 0.0001 - - 0.01 - - - 1 - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/launch/agent_bridge.launch.xml b/src/picknik_ur_multi_arm_gazebo_config/launch/agent_bridge.launch.xml deleted file mode 100644 index 1729a3c8..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/launch/agent_bridge.launch.xml +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/launch/robot_drivers_to_persist.launch.py b/src/picknik_ur_multi_arm_gazebo_config/launch/robot_drivers_to_persist.launch.py deleted file mode 100644 index 72aa95a2..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/launch/robot_drivers_to_persist.launch.py +++ /dev/null @@ -1,75 +0,0 @@ -# Copyright 2023 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - - -from launch import LaunchDescription -from launch_ros.actions import Node - -from moveit_studio_utils_py.launch_common import empty_gen -from moveit_studio_utils_py.system_config import ( - SystemConfigParser, -) - - -def generate_launch_description(): - system_config_parser = SystemConfigParser() - hardware_config = system_config_parser.get_hardware_config() - controller_config = system_config_parser.get_ros2_control_config() - - dashboard_client_node = Node( - package="ur_robot_driver", - executable="dashboard_client", - name="dashboard_client", - output="both", - emulate_tty=True, - parameters=[{"robot_ip": hardware_config["ip"]}], - ) - - protective_stop_manager_node = Node( - package="moveit_studio_ur_pstop_manager", - executable="protective_stop_manager_node", - name="protective_stop_manager_node", - output="both", - parameters=[ - { - "controllers_default_active": controller_config.get( - "controllers_active_at_startup", empty_gen() - ), - "controllers_default_not_active": controller_config.get( - "controllers_inactive_at_startup", empty_gen() - ), - } - ], - ) - - nodes_to_launch = [ - dashboard_client_node, - protective_stop_manager_node, - ] - - return LaunchDescription(nodes_to_launch) diff --git a/src/picknik_ur_multi_arm_gazebo_config/launch/sim/hardware_sim.launch.py b/src/picknik_ur_multi_arm_gazebo_config/launch/sim/hardware_sim.launch.py deleted file mode 100644 index d2715245..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/launch/sim/hardware_sim.launch.py +++ /dev/null @@ -1,352 +0,0 @@ -# Copyright 2023 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - - -import os -import re -import shlex - -from launch import LaunchDescription -from launch.actions import IncludeLaunchDescription, OpaqueFunction -from launch_ros.actions import Node - -from moveit_studio_utils_py.launch_common import get_launch_file, get_ros_path -from moveit_studio_utils_py.system_config import get_config_folder, SystemConfigParser - - -def path_pattern_change_for_gazebo(urdf_string): - """ - Replaces strings in a URDF file such as - package://package_name/path/to/file - to the actual full path of the file. - """ - data = urdf_string - package_expressions = re.findall("(package://([^//]*))", data) - for expr in set(package_expressions): - data = data.replace(expr[0], get_ros_path(expr[1])) - return data - - -def generate_simulation_description(context, *args, **settings): - world_path = settings.get( - "gazebo_world_path", - "description/simulation_worlds/space_station_blocks_world.sdf", - ) - use_gui = settings.get("gazebo_gui", False) - is_verbose = settings.get("gazebo_verbose", False) - - # Create a Gazebo world file that swaps out package:// paths with absolute path. - original_world_file = get_ros_path( - settings.get("gazebo_world_package_name", "picknik_ur_multi_arm_gazebo_config"), - world_path, - ) - modified_world_file = os.path.join( - get_config_folder(), "auto_created", "gazebo_world.sdf" - ) - with open(original_world_file, "r") as file: - world_sdf = path_pattern_change_for_gazebo(file.read()) - with open(modified_world_file, "w") as file: - file.write(world_sdf) - - # Launch Gazebo. - print(f"Starting Gazebo with world at {world_path}") - print(f"GUI: {use_gui}, Verbose: {is_verbose}") - - sim_args = "-r --render-engine ogre" - if is_verbose: - sim_args += " -v 4" - if not use_gui: - sim_args += " -s --headless-rendering" - - gazebo = IncludeLaunchDescription( - get_launch_file("ros_gz_sim", "launch/gz_sim.launch.py"), - launch_arguments=[("gz_args", [f"{sim_args} {modified_world_file}"])], - ) - return [gazebo] - - -def generate_launch_description(): - system_config_parser = SystemConfigParser() - optional_feature_setting = system_config_parser.get_optional_feature_configs() - - # The path to the auto_created urdf files - robot_urdf = system_config_parser.get_processed_urdf() - robot_urdf_ignition = path_pattern_change_for_gazebo(robot_urdf) - - # Launch Gazebo - gazebo = OpaqueFunction( - function=generate_simulation_description, kwargs=optional_feature_setting - ) - - init_pose_args = shlex.split("-x 0.0 -y 0.0 -z 1.03 -R 0.0 -P 0.0 -Y 0.0") - spawn_robot = Node( - package="ros_gz_sim", - executable="create", - output="both", - arguments=[ - "-string", - robot_urdf_ignition, - "-name", - "robot", - "-allow_renaming", - "true", - ] - + init_pose_args, - ) - - ######################## - # Camera Topic Bridges # - ######################## - # For the scene camera, enable RGB image topics only. - scene_image_rgb_ignition_bridge = Node( - package="ros_gz_image", - executable="image_bridge", - name="scene_image_rgb_ignition_bridge", - arguments=[ - "/scene_camera/image", - ], - remappings=[ - ("/scene_camera/image", "/scene_camera/color/image_raw"), - ], - output="both", - ) - scene_image_depth_ignition_bridge = Node( - package="ros_gz_image", - executable="image_bridge", - name="scene_image_depth_ignition_bridge", - arguments=[ - "/scene_camera/depth_image", - ], - remappings=[ - ( - "/scene_camera/depth_image", - "/scene_camera/depth/image_rect_raw", - ), - ], - output="both", - ) - - scene_camera_info_ignition_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="scene_camera_info_ignition_bridge", - arguments=[ - "/scene_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo", - ], - remappings=[ - ("/scene_camera/camera_info", "/scene_camera/color/camera_info"), - ], - output="both", - ) - - scene_camera_pointcloud_ignition_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="scene_camera_pointcloud_ignition_bridge", - arguments=[ - "/scene_mounted_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked", - ], - remappings=[ - ( - "/scene_mounted_camera/points", - "/scene_mounted_camera/depth/color/points", - ), - ], - output="both", - ) - - # For the wrist mounted camera, enable RGB and depth topics. - left_wrist_image_rgb_ignition_bridge = Node( - package="ros_gz_image", - executable="image_bridge", - name="left_wrist_image_rgb_ignition_bridge", - arguments=[ - "/left_wrist_mounted_camera/image", - ], - remappings=[ - ( - "/left_wrist_mounted_camera/image", - "/left_wrist_mounted_camera/color/image_raw", - ), - ], - output="both", - ) - left_wrist_image_depth_ignition_bridge = Node( - package="ros_gz_image", - executable="image_bridge", - name="left_wrist_image_depth_ignition_bridge", - arguments=[ - "/left_wrist_mounted_camera/depth_image", - ], - remappings=[ - ( - "/left_wrist_mounted_camera/depth_image", - "/left_wrist_mounted_camera/depth/image_rect_raw", - ), - ], - output="both", - ) - left_wrist_camera_pointcloud_ignition_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="left_wrist_camera_pointcloud_ignition_bridge", - arguments=[ - "/left_wrist_mounted_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked", - ], - remappings=[ - ( - "/left_wrist_mounted_camera/points", - "/left_wrist_mounted_camera/depth/color/points", - ), - ], - output="both", - ) - left_wrist_camera_info_ignition_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="left_wrist_camera_info_ignition_bridge", - arguments=[ - "/left_wrist_mounted_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo", - ], - remappings=[ - ( - "/left_wrist_mounted_camera/camera_info", - "/left_wrist_mounted_camera/color/camera_info", - ), - ], - output="both", - ) - - right_wrist_image_rgb_ignition_bridge = Node( - package="ros_gz_image", - executable="image_bridge", - name="right_wrist_image_rgb_ignition_bridge", - arguments=[ - "/right_wrist_mounted_camera/image", - ], - remappings=[ - ( - "/right_wrist_mounted_camera/image", - "/right_wrist_mounted_camera/color/image_raw", - ), - ], - output="both", - ) - right_wrist_image_depth_ignition_bridge = Node( - package="ros_gz_image", - executable="image_bridge", - name="right_wrist_image_depth_ignition_bridge", - arguments=[ - "/right_wrist_mounted_camera/depth_image", - ], - remappings=[ - ( - "/right_wrist_mounted_camera/depth_image", - "/right_wrist_mounted_camera/depth/image_rect_raw", - ), - ], - output="both", - ) - right_wrist_camera_pointcloud_ignition_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="right_wrist_camera_pointcloud_ignition_bridge", - arguments=[ - "/right_wrist_mounted_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked", - ], - remappings=[ - ( - "/right_wrist_mounted_camera/points", - "/right_wrist_mounted_camera/depth/color/points", - ), - ], - output="both", - ) - right_wrist_camera_info_ignition_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="right_wrist_camera_info_ignition_bridge", - arguments=[ - "/right_wrist_mounted_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo", - ], - remappings=[ - ( - "/right_wrist_mounted_camera/camera_info", - "/right_wrist_mounted_camera/color/camera_info", - ), - ], - output="both", - ) - - ####################### - # Force Torque Sensor # - ####################### - fts_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="fts_bridge", - arguments=[ - "/tcp_fts_sensor/ft_data@geometry_msgs/msg/WrenchStamped[ignition.msgs.Wrench", - ], - remappings=[ - ( - "/tcp_fts_sensor/ft_data", - "/force_torque_sensor_broadcaster/wrench", - ), - ], - output="both", - ) - - clock_bridge = Node( - package="ros_gz_bridge", - executable="parameter_bridge", - name="clock_bridge", - arguments=["/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock"], - output="both", - ) - - return LaunchDescription( - [ - scene_image_rgb_ignition_bridge, - scene_image_depth_ignition_bridge, - scene_camera_info_ignition_bridge, - scene_camera_pointcloud_ignition_bridge, - left_wrist_image_rgb_ignition_bridge, - left_wrist_camera_info_ignition_bridge, - left_wrist_image_depth_ignition_bridge, - left_wrist_camera_pointcloud_ignition_bridge, - right_wrist_image_rgb_ignition_bridge, - right_wrist_camera_info_ignition_bridge, - right_wrist_image_depth_ignition_bridge, - right_wrist_camera_pointcloud_ignition_bridge, - clock_bridge, - fts_bridge, - gazebo, - spawn_robot, - ] - ) diff --git a/src/picknik_ur_multi_arm_gazebo_config/launch/sim/robot_drivers_to_persist_sim.launch.py b/src/picknik_ur_multi_arm_gazebo_config/launch/sim/robot_drivers_to_persist_sim.launch.py deleted file mode 100644 index c6596305..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/launch/sim/robot_drivers_to_persist_sim.launch.py +++ /dev/null @@ -1,43 +0,0 @@ -# Copyright 2023 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - - -from launch import LaunchDescription -from launch_ros.actions import Node - - -def generate_launch_description(): - # Mock the UR Dashboard Client - mock_dashboard_client = Node( - package="moveit_studio_ur_pstop_manager", - executable="mock_ur_dashboard_client_node", - name="dashboard_client", - output="both", - ) - - return LaunchDescription([mock_dashboard_client]) diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/clear_snapshot.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/clear_snapshot.xml deleted file mode 100644 index 68c52c49..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/clear_snapshot.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/close_left_gripper.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/close_left_gripper.xml deleted file mode 100644 index ef168026..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/close_left_gripper.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/close_right_gripper.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/close_right_gripper.xml deleted file mode 100644 index 7e8268eb..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/close_right_gripper.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/interpolate_to_joint_state.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/interpolate_to_joint_state.xml deleted file mode 100644 index 811a5829..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/interpolate_to_joint_state.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_joint_state.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_joint_state.xml deleted file mode 100644 index 158cb6b5..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_joint_state.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_named_pose.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_named_pose.xml deleted file mode 100644 index 7d907dc7..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_named_pose.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_pose.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_pose.xml deleted file mode 100644 index 3a5086c3..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_to_pose.xml +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_two_arms.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/move_two_arms.xml deleted file mode 100644 index abd6ca73..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/move_two_arms.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/open_left_gripper.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/open_left_gripper.xml deleted file mode 100644 index 90e72edb..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/open_left_gripper.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/open_right_gripper.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/open_right_gripper.xml deleted file mode 100644 index 879aee52..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/open_right_gripper.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object.xml deleted file mode 100644 index 7bd28350..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object.xml +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_config.yaml b/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_config.yaml deleted file mode 100644 index 1697754c..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_config.yaml +++ /dev/null @@ -1,11 +0,0 @@ -SetupMTCPickObject: - # The lift vector points to the direction of the positive z-axis of the frame marked as the world frame. - world_frame_name: "world" - arm_group_name: "manipulator_right" - end_effector_group_name: "gripper" - end_effector_name: "right_ee" - hand_frame_name: "right_grasp_link" - end_effector_closed_pose_name: "close" - - approach_distance: 0.1 - lift_distance: 0.1 diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_left.yaml b/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_left.yaml deleted file mode 100644 index dae9e59a..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/pick_object_left.yaml +++ /dev/null @@ -1,11 +0,0 @@ -SetupMTCPickObject: - # The lift vector points to the direction of the positive z-axis of the frame marked as the world frame. - world_frame_name: "world" - arm_group_name: "manipulator_left" - end_effector_group_name: "gripper_left" - end_effector_name: "left_ee" - hand_frame_name: "left_grasp_link" - end_effector_closed_pose_name: "close_left" - - approach_distance: 0.1 - lift_distance: 0.1 diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/reactivate_gripper.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/reactivate_gripper.xml deleted file mode 100644 index a9666a46..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/reactivate_gripper.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/request_teleoperation.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/request_teleoperation.xml deleted file mode 100644 index 5565817b..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/request_teleoperation.xml +++ /dev/null @@ -1,53 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/reset_planning_scene.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/reset_planning_scene.xml deleted file mode 100644 index 8e43ac5a..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/reset_planning_scene.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/take_snapshot.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/take_snapshot.xml deleted file mode 100644 index de177011..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/take_snapshot.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/teleoperate.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/teleoperate.xml deleted file mode 100644 index 23614685..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/teleoperate.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/objectives/wait_for_trajectory_approval_if_user_available.xml b/src/picknik_ur_multi_arm_gazebo_config/objectives/wait_for_trajectory_approval_if_user_available.xml deleted file mode 100644 index 7abb4108..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/objectives/wait_for_trajectory_approval_if_user_available.xml +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/package.xml b/src/picknik_ur_multi_arm_gazebo_config/package.xml deleted file mode 100644 index bd7e860d..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/package.xml +++ /dev/null @@ -1,42 +0,0 @@ - - - picknik_ur_multi_arm_gazebo_config - 6.0.0 - - Experimental configuration package for dual UR arms. - - MoveIt Pro Maintainer - - BSD-3-Clause - - ament_cmake - - picknik_ur_base_config - picknik_ur_multi_arm_config - admittance_controller - kinematics_interface_kdl - moveit_planners_stomp - moveit_ros_perception - moveit_studio_agent - moveit_studio_behavior - moveit_studio_ur_pstop_manager - picknik_accessories - realsense2_description - robotiq_description - robotiq_controllers - trac_ik_kinematics_plugin - ur_description - ros_gz - - ament_lint_auto - ament_clang_format - ament_clang_tidy - ament_cmake_copyright - ament_cmake_lint_cmake - picknik_ament_copyright - ament_flake8 - - - ament_cmake - - diff --git a/src/picknik_ur_multi_arm_gazebo_config/waypoints/waypoints.yaml b/src/picknik_ur_multi_arm_gazebo_config/waypoints/waypoints.yaml deleted file mode 100644 index a21c8807..00000000 --- a/src/picknik_ur_multi_arm_gazebo_config/waypoints/waypoints.yaml +++ /dev/null @@ -1,241 +0,0 @@ -- description: '' - favorite: false - joint_group_names: - - gripper - - manipulator_right - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - right_robotiq_85_left_knuckle_joint - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - position: - - -1.1967178672123605e-06 - - 1.6294922237286515 - - -1.4075014169855327 - - -0.7172292331392662 - - -1.02642347033837 - - 1.6641204475784201 - - 0.0021283164147193555 - velocity: [] - name: Inspect Right -- description: '' - favorite: false - joint_group_names: - - gripper - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - right_robotiq_85_left_knuckle_joint - position: - - 0.7930685959474917 - velocity: [] - name: Right Closed Gripper -- description: Both arms are in a down position - favorite: true - joint_group_names: - - dual_arm_manipulator - - gripper - - manipulator_left - - manipulator_right - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - - right_robotiq_85_left_knuckle_joint - - left_robotiq_85_left_knuckle_joint - position: - - 5.12061324901879e-05 - - -1.4100637137602083 - - -0.6999914125130512 - - -2.1199174221931956 - - 1.6699393665105104 - - -4.32235198095441e-06 - - 3.109852643683551e-05 - - -1.410057083617756 - - -0.7000249972289894 - - -2.1200145056689625 - - 1.669979084378574 - - 1.3941351324319836e-05 - - 0 - - 0.7929 - velocity: [] - name: Home -- description: Both arms are in a down position - favorite: true - joint_group_names: - - dual_arm_manipulator - - manipulator_left - - manipulator_right - joint_state: - effort: [] - header: - frame_id: world - stamp: - nanosec: 0 - sec: 0 - name: - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - position: - - 8.581502470187843e-05 - - -1.5136764603659916 - - -1.799275792510518 - - -1.5993562600093492 - - 1.6699146867751609 - - -1.3363372068852196e-06 - - -6.064204568974674e-05 - - -1.5136764603659916 - - -1.71359599286716 - - -1.6564761264382546 - - 1.6699516917224972 - - -4.144793883897364e-05 - velocity: [] - name: Arms Down -- description: '' - favorite: true - joint_group_names: - - dual_arm_manipulator - - gripper - - gripper_left - - manipulator_left - - manipulator_right - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - - right_shoulder_pan_joint - - right_shoulder_lift_joint - - right_elbow_joint - - right_wrist_1_joint - - right_wrist_2_joint - - right_wrist_3_joint - - right_robotiq_85_left_knuckle_joint - - left_robotiq_85_left_knuckle_joint - position: - - -1.7095832296029843 - - -1.0500604029207294 - - -1.240154802498822 - - -0.8781638544771856 - - 1.6648887726908908 - - 0.0015182654301393564 - - 1.6294921509134237 - - -1.4075015036987286 - - -0.7172273447373503 - - -1.0264368393178898 - - 1.6641152815836038 - - 0.002125560625236223 - - 0.592406376256699 - - 0.592813686273142 - velocity: [] - name: Inspect -- description: '' - favorite: false - joint_group_names: - - gripper_left - - manipulator_left - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - left_robotiq_85_left_knuckle_joint - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - position: - - -2.0035421747362765e-06 - - -0.09976038781468007 - - -2.070732278116712 - - -1.7232074073646642 - - -0.9237947543320453 - - 1.5614126435536537 - - -0.057252780894965 - velocity: [] - name: Pick Red Left -- description: '' - favorite: false - joint_group_names: - - gripper_left - - manipulator_left - joint_state: - effort: [] - header: - frame_id: '' - stamp: - nanosec: 0 - sec: 0 - name: - - left_robotiq_85_left_knuckle_joint - - left_shoulder_pan_joint - - left_shoulder_lift_joint - - left_elbow_joint - - left_wrist_1_joint - - left_wrist_2_joint - - left_wrist_3_joint - position: - - -1.4413813976896227e-06 - - -1.71154795406197 - - -1.0535278711221066 - - -1.2324300583621988 - - -0.8837549907194114 - - 1.6672861150624345 - - 0.0013212085431139491 - velocity: [] - name: Inspect Left