From 9dd3086fea7f90525c6ff021ff537e7e7cad4012 Mon Sep 17 00:00:00 2001 From: Florian Walch <florian.walch@franka.de> Date: Wed, 7 Mar 2018 16:37:39 +0100 Subject: [PATCH] MoveIt config: Fix fake execution, update joint limits --- CHANGELOG.md | 4 ++ .../config/fake_controllers.yaml | 14 ++--- panda_moveit_config/config/joint_limits.yaml | 52 +++++++---------- panda_moveit_config/config/kinematics.yaml | 7 +-- panda_moveit_config/config/ompl_planning.yaml | 2 +- .../config/panda_arm_hand.srdf | 58 +++++++------------ 6 files changed, 51 insertions(+), 86 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 3c7654d..12045cb 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,10 @@ ## 0.4.0 - UNRELEASED + * Changes in `panda_moveit_config`: + * Updated joint limits from URDF + * Removed `home` poses + * Fixed fake execution * Added `mimic` tag for gripper fingers to URDF ## 0.3.0 - 2018-02-22 diff --git a/panda_moveit_config/config/fake_controllers.yaml b/panda_moveit_config/config/fake_controllers.yaml index 34a8e37..619aa5d 100644 --- a/panda_moveit_config/config/fake_controllers.yaml +++ b/panda_moveit_config/config/fake_controllers.yaml @@ -1,14 +1,5 @@ controller_list: - - name: fake_panda_controller - joints: - - panda_joint1 - - panda_joint2 - - panda_joint3 - - panda_joint4 - - panda_joint5 - - panda_joint6 - - panda_joint7 - - name: fake_panda_arm_hand_controller + - name: fake_panda_arm_controller joints: - panda_joint1 - panda_joint2 @@ -21,3 +12,6 @@ controller_list: joints: - panda_finger_joint1 - panda_finger_joint2 +initial: + - group: panda_arm_hand + pose: ready diff --git a/panda_moveit_config/config/joint_limits.yaml b/panda_moveit_config/config/joint_limits.yaml index 4323784..b254201 100644 --- a/panda_moveit_config/config/joint_limits.yaml +++ b/panda_moveit_config/config/joint_limits.yaml @@ -2,48 +2,38 @@ # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] joint_limits: - panda_finger_joint1: - has_velocity_limits: true - max_velocity: 0.3 - has_acceleration_limits: true - max_acceleration: 0.5 - panda_finger_joint2: - has_velocity_limits: true - max_velocity: 0.3 - has_acceleration_limits: true - max_acceleration: 0.5 panda_joint1: has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 0.5 + max_velocity: 2.3925 + has_acceleration_limits: false + max_acceleration: 0 panda_joint2: has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 0.5 + max_velocity: 2.3925 + has_acceleration_limits: false + max_acceleration: 0 panda_joint3: has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 0.5 + max_velocity: 2.3925 + has_acceleration_limits: false + max_acceleration: 0 panda_joint4: has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 0.5 + max_velocity: 2.3925 + has_acceleration_limits: false + max_acceleration: 0 panda_joint5: has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 0.5 + max_velocity: 2.871 + has_acceleration_limits: false + max_acceleration: 0 panda_joint6: has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 0.5 + max_velocity: 2.871 + has_acceleration_limits: false + max_acceleration: 0 panda_joint7: has_velocity_limits: true - max_velocity: 0.5 - has_acceleration_limits: true - max_acceleration: 0.5 + max_velocity: 2.871 + has_acceleration_limits: false + max_acceleration: 0 diff --git a/panda_moveit_config/config/kinematics.yaml b/panda_moveit_config/config/kinematics.yaml index c64ffe3..7ec1735 100644 --- a/panda_moveit_config/config/kinematics.yaml +++ b/panda_moveit_config/config/kinematics.yaml @@ -1,9 +1,4 @@ -panda: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 -panda_arm_hand: +panda_arm: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.005 diff --git a/panda_moveit_config/config/ompl_planning.yaml b/panda_moveit_config/config/ompl_planning.yaml index 9251f54..17d4c5a 100644 --- a/panda_moveit_config/config/ompl_planning.yaml +++ b/panda_moveit_config/config/ompl_planning.yaml @@ -120,7 +120,7 @@ planner_configs: sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 max_failures: 5000 # maximum consecutive failure limit. default: 5000 -panda: +panda_arm: planner_configs: - SBLkConfigDefault - ESTkConfigDefault diff --git a/panda_moveit_config/config/panda_arm_hand.srdf b/panda_moveit_config/config/panda_arm_hand.srdf index 56981c7..bfcde8d 100644 --- a/panda_moveit_config/config/panda_arm_hand.srdf +++ b/panda_moveit_config/config/panda_arm_hand.srdf @@ -30,26 +30,26 @@ <chain base_link="panda_link0" tip_link="panda_link8" /> </group> <group name="panda_arm_hand"> - <link name="panda_link0" /> - <link name="panda_link1" /> - <link name="panda_link2" /> - <link name="panda_link3" /> - <link name="panda_link4" /> - <link name="panda_link5" /> - <link name="panda_link6" /> - <link name="panda_link7" /> - <link name="panda_link8" /> - <link name="panda_hand" /> - <joint name="panda_joint1" /> - <joint name="panda_joint2" /> - <joint name="panda_joint3" /> - <joint name="panda_joint4" /> - <joint name="panda_joint5" /> - <joint name="panda_joint6" /> - <joint name="panda_joint7" /> - <joint name="panda_joint8" /> - <joint name="panda_hand_joint" /> - <chain base_link="panda_link0" tip_link="panda_hand" /> + <link name="panda_link0" /> + <link name="panda_link1" /> + <link name="panda_link2" /> + <link name="panda_link3" /> + <link name="panda_link4" /> + <link name="panda_link5" /> + <link name="panda_link6" /> + <link name="panda_link7" /> + <link name="panda_link8" /> + <link name="panda_hand" /> + <joint name="panda_joint1" /> + <joint name="panda_joint2" /> + <joint name="panda_joint3" /> + <joint name="panda_joint4" /> + <joint name="panda_joint5" /> + <joint name="panda_joint6" /> + <joint name="panda_joint7" /> + <joint name="panda_joint8" /> + <joint name="panda_hand_joint" /> + <chain base_link="panda_link0" tip_link="panda_hand" /> </group> <group name="hand"> <link name="panda_hand" /> @@ -59,15 +59,6 @@ <joint name="panda_finger_joint2" /> </group> <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> - <group_state name="home" group="panda_arm"> - <joint name="panda_joint1" value="0" /> - <joint name="panda_joint2" value="0" /> - <joint name="panda_joint3" value="0" /> - <joint name="panda_joint4" value="0" /> - <joint name="panda_joint5" value="0" /> - <joint name="panda_joint6" value="0" /> - <joint name="panda_joint7" value="0.785" /> - </group_state> <group_state name="ready" group="panda_arm"> <joint name="panda_joint1" value="0" /> <joint name="panda_joint2" value="-0.785" /> @@ -77,15 +68,6 @@ <joint name="panda_joint6" value="1.571" /> <joint name="panda_joint7" value="0.785" /> </group_state> - <group_state name="home" group="panda_arm_hand"> - <joint name="panda_joint1" value="0" /> - <joint name="panda_joint2" value="0" /> - <joint name="panda_joint3" value="0" /> - <joint name="panda_joint4" value="0" /> - <joint name="panda_joint5" value="0" /> - <joint name="panda_joint6" value="0" /> - <joint name="panda_joint7" value="0.785" /> - </group_state> <group_state name="ready" group="panda_arm_hand"> <joint name="panda_joint1" value="0" /> <joint name="panda_joint2" value="-0.785" /> -- GitLab