From 5b4e947512805b1d4b715b68e2e9aceffb4075d7 Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Wed, 25 Aug 2021 15:32:44 +0200 Subject: [PATCH 1/8] Converts 'panda.srdf' to a 'panda.srdf.xacro' file (#18) This was done since the `moveit_setup_assistant` currently doesn't propagate `xacro` arguments you supply to the `urdf.xacro` file (see [this issue](https://github.com/ros-planning/moveit/issues/1691)). We need to manually add a way to enable or disable the gripper. This can be done by creating a `panda.srdf.xacro` file. --- config/hand.xacro | 47 ++++++++++++++++ config/panda.srdf | 97 ---------------------------------- config/panda.srdf.xacro | 23 ++++++++ config/panda_arm.xacro | 62 ++++++++++++++++++++++ launch/demo.launch | 4 ++ launch/move_group.launch | 7 ++- launch/planning_context.launch | 5 +- 7 files changed, 145 insertions(+), 100 deletions(-) create mode 100644 config/hand.xacro delete mode 100644 config/panda.srdf create mode 100644 config/panda.srdf.xacro create mode 100644 config/panda_arm.xacro diff --git a/config/hand.xacro b/config/hand.xacro new file mode 100644 index 0000000..c72e93e --- /dev/null +++ b/config/hand.xacro @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/config/panda.srdf b/config/panda.srdf deleted file mode 100644 index c9d7ea0..0000000 --- a/config/panda.srdf +++ /dev/null @@ -1,97 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/config/panda.srdf.xacro b/config/panda.srdf.xacro new file mode 100644 index 0000000..0541bf3 --- /dev/null +++ b/config/panda.srdf.xacro @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/config/panda_arm.xacro b/config/panda_arm.xacro new file mode 100644 index 0000000..4c04502 --- /dev/null +++ b/config/panda_arm.xacro @@ -0,0 +1,62 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/demo.launch b/launch/demo.launch index a88e16f..c26e366 100644 --- a/launch/demo.launch +++ b/launch/demo.launch @@ -11,6 +11,9 @@ + + + @@ -51,6 +54,7 @@ + diff --git a/launch/move_group.launch b/launch/move_group.launch index 154ce53..5095a3f 100644 --- a/launch/move_group.launch +++ b/launch/move_group.launch @@ -21,6 +21,10 @@ + + + + + @@ -63,7 +68,7 @@ + file="$(dirname)/planning_pipeline.launch.xml"> diff --git a/launch/planning_context.launch b/launch/planning_context.launch index ef17b2b..27d5a3a 100644 --- a/launch/planning_context.launch +++ b/launch/planning_context.launch @@ -1,15 +1,16 @@ + - + - + From 02761a1864e6668f73d937d1fef0ea34d565ed0f Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Wed, 25 Aug 2021 15:36:00 +0200 Subject: [PATCH 2/8] Adds perception tutorial camera files (#19) This commit makes sure that the camera configuration files, that are used in the [perception pipeline tutorial](https://ros-planning.github.io/moveit_tutorials/doc/perception_pipeline/perception_pipeline_tutorial.html?highlight=perception%20tutorial) are present in the configuration repository. --- config/sensors_3d.yaml | 23 ----------------------- config/sensors_kinect_depthmap.yaml | 11 +++++++++++ config/sensors_kinect_pointcloud.yaml | 9 +++++++++ launch/sensor_manager.launch.xml | 5 ++++- 4 files changed, 24 insertions(+), 24 deletions(-) delete mode 100644 config/sensors_3d.yaml create mode 100644 config/sensors_kinect_depthmap.yaml create mode 100644 config/sensors_kinect_pointcloud.yaml diff --git a/config/sensors_3d.yaml b/config/sensors_3d.yaml deleted file mode 100644 index 0713b61..0000000 --- a/config/sensors_3d.yaml +++ /dev/null @@ -1,23 +0,0 @@ -# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it -sensors: - - filtered_cloud_topic: filtered_cloud - max_range: 5.0 - max_update_rate: 1.0 - padding_offset: 0.1 - padding_scale: 1.0 - point_cloud_topic: /head_mount_kinect/depth_registered/points - point_subsample: 1 - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater - - far_clipping_plane_distance: 5.0 - filtered_cloud_topic: filtered_cloud - image_topic: /head_mount_kinect/depth_registered/image_raw - max_range: 5.0 - max_update_rate: 1.0 - near_clipping_plane_distance: 0.3 - padding_offset: 0.03 - padding_scale: 4.0 - point_cloud_topic: /head_mount_kinect/depth_registered/points - point_subsample: 1 - queue_size: 5 - sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater - shadow_threshold: 0.2 \ No newline at end of file diff --git a/config/sensors_kinect_depthmap.yaml b/config/sensors_kinect_depthmap.yaml new file mode 100644 index 0000000..9538fe0 --- /dev/null +++ b/config/sensors_kinect_depthmap.yaml @@ -0,0 +1,11 @@ +sensors: + - sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater + image_topic: /camera/depth_registered/image_raw + queue_size: 5 + near_clipping_plane_distance: 0.3 + far_clipping_plane_distance: 5.0 + shadow_threshold: 0.2 + padding_scale: 4.0 + padding_offset: 0.03 + max_update_rate: 1.0 + filtered_cloud_topic: filtered_cloud diff --git a/config/sensors_kinect_pointcloud.yaml b/config/sensors_kinect_pointcloud.yaml new file mode 100644 index 0000000..92e7095 --- /dev/null +++ b/config/sensors_kinect_pointcloud.yaml @@ -0,0 +1,9 @@ +sensors: + - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater + point_cloud_topic: /camera/depth_registered/points + max_range: 5.0 + point_subsample: 1 + padding_offset: 0.1 + padding_scale: 1.0 + max_update_rate: 1.0 + filtered_cloud_topic: filtered_cloud diff --git a/launch/sensor_manager.launch.xml b/launch/sensor_manager.launch.xml index 17279dd..dd9d3ad 100644 --- a/launch/sensor_manager.launch.xml +++ b/launch/sensor_manager.launch.xml @@ -3,10 +3,13 @@ - + + + + From 16ea1d8232bd221eb1811218bdede7e41a9a5bdf Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Wed, 25 Aug 2021 15:40:37 +0200 Subject: [PATCH 3/8] Adds rviz_tutorial argument (#20) This commit adds the 'rviz_tutorial' argument to the 'demo.launch' file. This argument is needed for the [quickstart_in_rviz_tutorial](https://ros-planning.github.io/moveit_tutorials/doc/quickstart_in_rviz/quickstart_in_rviz_tutorial.html). --- launch/demo.launch | 3 + launch/moveit.rviz | 723 ++++++++------------------------------ launch/moveit_empty.rviz | 99 ++++++ launch/moveit_rviz.launch | 8 +- package.xml | 4 +- 5 files changed, 262 insertions(+), 575 deletions(-) create mode 100644 launch/moveit_empty.rviz diff --git a/launch/demo.launch b/launch/demo.launch index c26e366..5b9a2c7 100644 --- a/launch/demo.launch +++ b/launch/demo.launch @@ -20,6 +20,8 @@ + + + diff --git a/launch/moveit.rviz b/launch/moveit.rviz index c4d6ae5..3f11f09 100644 --- a/launch/moveit.rviz +++ b/launch/moveit.rviz @@ -3,10 +3,9 @@ Panels: Help Height: 84 Name: Displays Property Tree Widget: - Expanded: - - /MotionPlanning1 - Splitter Ratio: 0.74256 - Tree Height: 664 + Expanded: ~ + Splitter Ratio: 0.7425600290298462 + Tree Height: 425 - Class: rviz/Help Name: Help - Class: rviz/Views @@ -14,6 +13,12 @@ Panels: - /Current View1 Name: Views Splitter Ratio: 0.5 + - Class: rviz_visual_tools/RvizVisualToolsGui + Name: RvizVisualToolsGui +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 Visualization Manager: Class: "" Displays: @@ -23,7 +28,7 @@ Visualization Manager: Color: 160; 160; 164 Enabled: true Line Style: - Line Width: 0.03 + Line Width: 0.029999999329447746 Value: Lines Name: Grid Normal Cell Count: 0 @@ -35,655 +40,233 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: Value: true - - Class: moveit_rviz_plugin/MotionPlanning + - Class: rviz/MarkerArray Enabled: true - MoveIt_Goal_Tolerance: 0 - MoveIt_Planning_Time: 5 - MoveIt_Use_Constraint_Aware_IK: true - MoveIt_Warehouse_Host: 127.0.0.1 - MoveIt_Warehouse_Port: 33829 - Name: MotionPlanning - Planned Path: - Links: - base_bellow_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - base_footprint: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bl_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bl_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bl_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - br_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - br_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - br_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - double_stereo_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fl_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fl_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fl_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_ir_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_rgb_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_prosilica_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_plate_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_tilt_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_motor_accelerometer_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_palm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - laser_tilt_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_forearm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_l_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_l_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_motor_accelerometer_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_palm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_r_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_r_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_shoulder_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_shoulder_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_upper_arm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_wrist_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_wrist_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - sensor_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - torso_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Loop Animation: true - Robot Alpha: 0.5 - Show Robot Collision: false - Show Robot Visual: true - Show Trail: false - State Display Time: 0.05 s - Trajectory Topic: move_group/display_planned_path - Planning Metrics: - Payload: 1 - Show Joint Torques: false - Show Manipulability: false - Show Manipulability Index: false - Show Weight Limit: false - Planning Request: - Colliding Link Color: 255; 0; 0 - Goal State Alpha: 1 - Goal State Color: 250; 128; 0 - Interactive Marker Size: 0 - Joint Violation Color: 255; 0; 255 - Planning Group: left_arm - Query Goal State: true - Query Start State: false - Show Workspace: false - Start State Alpha: 1 - Start State Color: 0; 255; 0 + Marker Topic: /rviz_visual_tools + Name: MarkerArray + Namespaces: + {} + Queue Size: 100 + Value: true + - Class: moveit_rviz_plugin/Trajectory + Color Enabled: false + Enabled: true + Interrupt Display: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + panda_hand: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_leftfinger: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link0: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link7: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_link8: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + panda_rightfinger: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: false + Name: Trajectory + Robot Alpha: 0.5 + Robot Color: 150; 50; 150 + Robot Description: robot_description + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trail Step Size: 1 + Trajectory Topic: move_group/display_planned_path + Value: true + - Class: moveit_rviz_plugin/PlanningScene + Enabled: true + Move Group Namespace: "" + Name: PlanningScene Planning Scene Topic: move_group/monitored_planning_scene Robot Description: robot_description Scene Geometry: - Scene Alpha: 1 + Scene Alpha: 0.8999999761581421 Scene Color: 50; 230; 50 - Scene Display Time: 0.2 + Scene Display Time: 0.20000000298023224 Show Scene Geometry: true Voxel Coloring: Z-Axis Voxel Rendering: Occupied Voxels Scene Robot: Attached Body Color: 150; 50; 150 Links: - base_bellow_link: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + panda_hand: Alpha: 1 Show Axes: false Show Trail: false Value: true - base_footprint: + panda_leftfinger: Alpha: 1 Show Axes: false Show Trail: false Value: true - base_link: + panda_link0: Alpha: 1 Show Axes: false Show Trail: false Value: true - bl_caster_l_wheel_link: + panda_link1: Alpha: 1 Show Axes: false Show Trail: false Value: true - bl_caster_r_wheel_link: + panda_link2: Alpha: 1 Show Axes: false Show Trail: false Value: true - bl_caster_rotation_link: + panda_link3: Alpha: 1 Show Axes: false Show Trail: false Value: true - br_caster_l_wheel_link: + panda_link4: Alpha: 1 Show Axes: false Show Trail: false Value: true - br_caster_r_wheel_link: + panda_link5: Alpha: 1 Show Axes: false Show Trail: false Value: true - br_caster_rotation_link: + panda_link6: Alpha: 1 Show Axes: false Show Trail: false Value: true - double_stereo_link: + panda_link7: Alpha: 1 Show Axes: false Show Trail: false Value: true - fl_caster_l_wheel_link: + panda_link8: Alpha: 1 Show Axes: false Show Trail: false Value: true - fl_caster_r_wheel_link: + panda_rightfinger: Alpha: 1 Show Axes: false Show Trail: false Value: true - fl_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_l_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_r_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - fr_caster_rotation_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_ir_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_kinect_rgb_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_mount_prosilica_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_plate_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - head_tilt_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_forearm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_l_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_motor_accelerometer_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_palm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_gripper_r_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_shoulder_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_upper_arm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - l_wrist_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - laser_tilt_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_elbow_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_forearm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_l_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_l_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_motor_accelerometer_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_palm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_r_finger_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_gripper_r_finger_tip_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_shoulder_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_shoulder_pan_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_upper_arm_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_wrist_flex_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - r_wrist_roll_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - sensor_mount_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - torso_lift_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Robot Alpha: 0.5 - Show Scene Robot: true + Robot Alpha: 1 + Show Robot Collision: false + Show Robot Visual: true Value: true Enabled: true Global Options: Background Color: 48; 48; 48 + Default Light: true Fixed Frame: panda_link0 + Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select + - Class: rviz_visual_tools/KeyTool Value: true Views: Current: Class: rviz/XYOrbit - Distance: 2.9965 + Distance: 2.827594041824341 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 Focal Point: - X: 0.113567 - Y: 0.10592 - Z: 2.23518e-07 + X: 0.11356700211763382 + Y: 0.10592000186443329 + Z: 2.2351800055275817e-07 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false Name: Current View - Near Clip Distance: 0.01 - Pitch: 0.509797 - Target Frame: /panda_link0 - Value: XYOrbit (rviz) - Yaw: 5.65995 + Near Clip Distance: 0.009999999776482582 + Pitch: 0.47020357847213745 + Target Frame: panda_link0 + Yaw: 6.06496000289917 Saved: ~ Window Geometry: Displays: collapsed: false - Height: 1337 + Height: 741 Help: collapsed: false Hide Left Dock: false Hide Right Dock: false - Motion Planning: + QMainWindow State: 000000ff00000000fd0000000100000000000001780000028bfc020000000efb000000100044006900730070006c006100790073010000003d0000023a000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000026d000000b5000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb0000002e004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d00200053006c0069006400650072010000026f000000480000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670000000294000002410000000000000000fb00000024005200760069007a00560069007300750061006c0054006f006f006c0073004700750069010000027d0000004b0000004100fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000034f000001fb0000000000000000fb000000120020002d00200053006c006900640065007201000002df000000480000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000032d000001fb0000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb0000003c005400720061006a006500630074006f007200790020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016000003d80000028b00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + RvizVisualToolsGui: + collapsed: false + Trajectory - Trajectory Slider: collapsed: false - QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Views: collapsed: false - Width: 1828 - X: 459 - Y: -243 + Width: 1366 + X: 1920 + Y: 629 diff --git a/launch/moveit_empty.rviz b/launch/moveit_empty.rviz new file mode 100644 index 0000000..0b6a7f4 --- /dev/null +++ b/launch/moveit_empty.rviz @@ -0,0 +1,99 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.742560029 + Tree Height: 1100 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_visual_tools/RvizVisualToolsGui + Name: RvizVisualToolsGui +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /rviz_visual_tools + Name: MarkerArray + Namespaces: + {} + Queue Size: 100 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: panda_link0 + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz_visual_tools/KeyTool + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.82759404 + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.113567002 + Y: 0.105920002 + Z: 2.23518001e-07 + Focal Shape Fixed Size: true + Focal Shape Size: 0.0500000007 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Pitch: 0.369797021 + Target Frame: panda_link0 + Value: XYOrbit (rviz) + Yaw: 0.246767148 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1353 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000001000000000000016a000004e6fc020000000afb000000100044006900730070006c0061007900730100000042000004e6000000dc00fffffffb0000000800480065006c00700000000342000000bb0000007500fffffffb0000000a00560069006500770073000000026d000000b5000000b500fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb0000002e004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d00200053006c00690064006500720000000000ffffffff0000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000030d0000023d0000000000000000fb00000024005200760069007a00560069007300750061006c0054006f006f006c007300470075006900000004bd0000008d0000004800fffffffb000000120020002d00200053006c00690064006500720000000000ffffffff0000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000034f000001fb000000000000000000000463000004e600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + RvizVisualToolsGui: + collapsed: false + Views: + collapsed: false + Width: 1491 + X: 1067 + Y: 27 diff --git a/launch/moveit_rviz.launch b/launch/moveit_rviz.launch index a4605c0..77f32ee 100644 --- a/launch/moveit_rviz.launch +++ b/launch/moveit_rviz.launch @@ -4,9 +4,11 @@ - - - + + + + + diff --git a/package.xml b/package.xml index d35ac69..53ad179 100644 --- a/package.xml +++ b/package.xml @@ -29,9 +29,9 @@ rviz tf2_ros xacro + moveit_visual_tools - franka_description - + franka_description From be40ff93ea52ce0d529f04f20ac99318cefb987e Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Fri, 27 Aug 2021 14:18:54 +0200 Subject: [PATCH 4/8] Fixes custom planner ns bug (#46) This commit fixes a custom planner ns bug that was introduced by the `setup_assistant` (see https://github.com/ros-planning/moveit/pull/2842). --- launch/move_group.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/move_group.launch b/launch/move_group.launch index 5095a3f..18da573 100644 --- a/launch/move_group.launch +++ b/launch/move_group.launch @@ -67,7 +67,7 @@ - From 9ccf59081aadfb9e3790fa17e6f73754e381fa10 Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Fri, 27 Aug 2021 14:24:57 +0200 Subject: [PATCH 5/8] Adds missing package dependencies (#48) This commit adds several missing package dependencies. These package dependencies were commented to prevent installing gazebo be default. It was merged to be consistent with the 'moveit_setup_assistant' (see https://github.com/ros-planning/moveit/pull/2839). --- package.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/package.xml b/package.xml index 53ad179..e77ab87 100644 --- a/package.xml +++ b/package.xml @@ -30,6 +30,10 @@ tf2_ros xacro moveit_visual_tools + + + franka_description From 6d6ce63d15bafcbf5199ac6d7909067c9a694611 Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Fri, 27 Aug 2021 14:27:34 +0200 Subject: [PATCH 6/8] Fix panda self-collisions (#49) This commit contains a fix for self-collisions that were introduced in https://github.com/frankaemika/franka_ros/releases/tag/0.8.0. Franka changed the collision goemetries from meshes to shapes. Since these geometries are too coarse some joints are now in self collision. This commit might be removed in the future if the issue is fixed in the upstream. --- config/panda_arm.xacro | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/config/panda_arm.xacro b/config/panda_arm.xacro index 4c04502..34dfef8 100644 --- a/config/panda_arm.xacro +++ b/config/panda_arm.xacro @@ -58,5 +58,13 @@ + + + From 9618a69704ac40f265340313cf2ac335cfdf6590 Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Fri, 27 Aug 2021 14:29:23 +0200 Subject: [PATCH 7/8] Adds the panda_control_moveit_rviz launch file (#50) This commit adds the panda_control_moveit_rviz launch file. This file can be used to control a real robot using MoveIt. --- config/panda_gripper_moveit_controllers.yaml | 20 +++++ config/panda_moveit_controllers.yaml | 13 ++++ config/ros_controllers.yaml | 55 +------------- launch/demo_gazebo.launch | 74 ------------------- launch/gazebo.launch | 23 ------ launch/move_group.launch | 3 +- launch/panda_control_moveit_rviz.launch | 30 ++++++++ ...ipper_moveit_controller_manager.launch.xml | 12 +++ launch/panda_moveit.launch | 10 +++ ...panda_moveit_controller_manager.launch.xml | 2 +- launch/ros_controllers.launch | 2 +- 11 files changed, 90 insertions(+), 154 deletions(-) create mode 100644 config/panda_gripper_moveit_controllers.yaml create mode 100644 config/panda_moveit_controllers.yaml delete mode 100644 launch/demo_gazebo.launch delete mode 100644 launch/gazebo.launch create mode 100644 launch/panda_control_moveit_rviz.launch create mode 100644 launch/panda_gripper_moveit_controller_manager.launch.xml create mode 100644 launch/panda_moveit.launch diff --git a/config/panda_gripper_moveit_controllers.yaml b/config/panda_gripper_moveit_controllers.yaml new file mode 100644 index 0000000..8a6efb6 --- /dev/null +++ b/config/panda_gripper_moveit_controllers.yaml @@ -0,0 +1,20 @@ +controller_list: + - name: position_joint_trajectory_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: true + joints: + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 + - name: franka_gripper + action_ns: gripper_action + type: GripperCommand + default: true + joints: + - panda_finger_joint1 + - panda_finger_joint2 diff --git a/config/panda_moveit_controllers.yaml b/config/panda_moveit_controllers.yaml new file mode 100644 index 0000000..3cd123f --- /dev/null +++ b/config/panda_moveit_controllers.yaml @@ -0,0 +1,13 @@ +controller_list: + - name: position_joint_trajectory_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: true + joints: + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 diff --git a/config/ros_controllers.yaml b/config/ros_controllers.yaml index a67b290..6ad2d06 100644 --- a/config/ros_controllers.yaml +++ b/config/ros_controllers.yaml @@ -17,57 +17,4 @@ hardware_interface: - panda_joint6 - panda_joint7 - panda_finger_joint1 - sim_control_mode: 1 # 0: position, 1: velocity -# Publish all joint states -# Creates the /joint_states topic necessary in ROS -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 50 -controller_list: - [] -position_joint_trajectory_controller: - type: position_controllers/JointTrajectoryController - joints: - - panda_joint1 - - panda_joint2 - - panda_joint3 - - panda_joint4 - - panda_joint5 - - panda_joint6 - - panda_joint7 - gains: - panda_joint1: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - panda_joint2: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - panda_joint3: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - panda_joint4: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - panda_joint5: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - panda_joint6: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - panda_joint7: - p: 100 - d: 1 - i: 1 - i_clamp: 1 \ No newline at end of file + sim_control_mode: 1 # 0: position, 1: velocity \ No newline at end of file diff --git a/launch/demo_gazebo.launch b/launch/demo_gazebo.launch deleted file mode 100644 index caae7cd..0000000 --- a/launch/demo_gazebo.launch +++ /dev/null @@ -1,74 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - [/joint_states] - - - [move_group/fake_controller_joint_states] - [/joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/gazebo.launch b/launch/gazebo.launch deleted file mode 100644 index 16adbad..0000000 --- a/launch/gazebo.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/move_group.launch b/launch/move_group.launch index 18da573..f746839 100644 --- a/launch/move_group.launch +++ b/launch/move_group.launch @@ -76,7 +76,8 @@ - + + diff --git a/launch/panda_control_moveit_rviz.launch b/launch/panda_control_moveit_rviz.launch new file mode 100644 index 0000000..ce41e83 --- /dev/null +++ b/launch/panda_control_moveit_rviz.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/panda_gripper_moveit_controller_manager.launch.xml b/launch/panda_gripper_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..e275653 --- /dev/null +++ b/launch/panda_gripper_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/launch/panda_moveit.launch b/launch/panda_moveit.launch new file mode 100644 index 0000000..3010bd7 --- /dev/null +++ b/launch/panda_moveit.launch @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/launch/panda_moveit_controller_manager.launch.xml b/launch/panda_moveit_controller_manager.launch.xml index febf584..f1123a7 100644 --- a/launch/panda_moveit_controller_manager.launch.xml +++ b/launch/panda_moveit_controller_manager.launch.xml @@ -9,5 +9,5 @@ - + diff --git a/launch/ros_controllers.launch b/launch/ros_controllers.launch index 85f011b..590c9c9 100644 --- a/launch/ros_controllers.launch +++ b/launch/ros_controllers.launch @@ -6,6 +6,6 @@ + output="screen" args="position_joint_trajectory_controller"/> From b23db79771a42ec1fd2f1cf72c95bec57c2fccbe Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Mon, 30 Aug 2021 14:18:39 +0200 Subject: [PATCH 8/8] Fixes *_planning_pipeline.launch template input args defaults (#56) This commit makes sure that all input arguments of the *_planning_pipeline.launch templates do have a default value. --- launch/chomp_planning_pipeline.launch.xml | 6 +++--- launch/ompl_planning_pipeline.launch.xml | 6 +++--- ...z_industrial_motion_planner_planning_pipeline.launch.xml | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/launch/chomp_planning_pipeline.launch.xml b/launch/chomp_planning_pipeline.launch.xml index bbcaba9..8482643 100644 --- a/launch/chomp_planning_pipeline.launch.xml +++ b/launch/chomp_planning_pipeline.launch.xml @@ -2,12 +2,12 @@ - - + + - - + + diff --git a/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml index 82a5a48..b6bf529 100644 --- a/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml +++ b/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml @@ -5,7 +5,7 @@ - +