Skip to content
Snippets Groups Projects
Commit 9dd3086f authored by Florian Walch's avatar Florian Walch
Browse files

MoveIt config: Fix fake execution, update joint limits

parent c3582450
No related branches found
No related tags found
No related merge requests found
...@@ -2,6 +2,10 @@ ...@@ -2,6 +2,10 @@
## 0.4.0 - UNRELEASED ## 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 * Added `mimic` tag for gripper fingers to URDF
## 0.3.0 - 2018-02-22 ## 0.3.0 - 2018-02-22
......
controller_list: controller_list:
- name: fake_panda_controller - name: fake_panda_arm_controller
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
- name: fake_panda_arm_hand_controller
joints: joints:
- panda_joint1 - panda_joint1
- panda_joint2 - panda_joint2
...@@ -21,3 +12,6 @@ controller_list: ...@@ -21,3 +12,6 @@ controller_list:
joints: joints:
- panda_finger_joint1 - panda_finger_joint1
- panda_finger_joint2 - panda_finger_joint2
initial:
- group: panda_arm_hand
pose: ready
...@@ -2,48 +2,38 @@ ...@@ -2,48 +2,38 @@
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] # 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 can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_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: panda_joint1:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.5 max_velocity: 2.3925
has_acceleration_limits: true has_acceleration_limits: false
max_acceleration: 0.5 max_acceleration: 0
panda_joint2: panda_joint2:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.5 max_velocity: 2.3925
has_acceleration_limits: true has_acceleration_limits: false
max_acceleration: 0.5 max_acceleration: 0
panda_joint3: panda_joint3:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.5 max_velocity: 2.3925
has_acceleration_limits: true has_acceleration_limits: false
max_acceleration: 0.5 max_acceleration: 0
panda_joint4: panda_joint4:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.5 max_velocity: 2.3925
has_acceleration_limits: true has_acceleration_limits: false
max_acceleration: 0.5 max_acceleration: 0
panda_joint5: panda_joint5:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.5 max_velocity: 2.871
has_acceleration_limits: true has_acceleration_limits: false
max_acceleration: 0.5 max_acceleration: 0
panda_joint6: panda_joint6:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.5 max_velocity: 2.871
has_acceleration_limits: true has_acceleration_limits: false
max_acceleration: 0.5 max_acceleration: 0
panda_joint7: panda_joint7:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 0.5 max_velocity: 2.871
has_acceleration_limits: true has_acceleration_limits: false
max_acceleration: 0.5 max_acceleration: 0
panda: panda_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
panda_arm_hand:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005 kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005 kinematics_solver_timeout: 0.005
......
...@@ -120,7 +120,7 @@ planner_configs: ...@@ -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 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 dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 5000 # maximum consecutive failure limit. default: 5000 max_failures: 5000 # maximum consecutive failure limit. default: 5000
panda: panda_arm:
planner_configs: planner_configs:
- SBLkConfigDefault - SBLkConfigDefault
- ESTkConfigDefault - ESTkConfigDefault
......
...@@ -30,26 +30,26 @@ ...@@ -30,26 +30,26 @@
<chain base_link="panda_link0" tip_link="panda_link8" /> <chain base_link="panda_link0" tip_link="panda_link8" />
</group> </group>
<group name="panda_arm_hand"> <group name="panda_arm_hand">
<link name="panda_link0" /> <link name="panda_link0" />
<link name="panda_link1" /> <link name="panda_link1" />
<link name="panda_link2" /> <link name="panda_link2" />
<link name="panda_link3" /> <link name="panda_link3" />
<link name="panda_link4" /> <link name="panda_link4" />
<link name="panda_link5" /> <link name="panda_link5" />
<link name="panda_link6" /> <link name="panda_link6" />
<link name="panda_link7" /> <link name="panda_link7" />
<link name="panda_link8" /> <link name="panda_link8" />
<link name="panda_hand" /> <link name="panda_hand" />
<joint name="panda_joint1" /> <joint name="panda_joint1" />
<joint name="panda_joint2" /> <joint name="panda_joint2" />
<joint name="panda_joint3" /> <joint name="panda_joint3" />
<joint name="panda_joint4" /> <joint name="panda_joint4" />
<joint name="panda_joint5" /> <joint name="panda_joint5" />
<joint name="panda_joint6" /> <joint name="panda_joint6" />
<joint name="panda_joint7" /> <joint name="panda_joint7" />
<joint name="panda_joint8" /> <joint name="panda_joint8" />
<joint name="panda_hand_joint" /> <joint name="panda_hand_joint" />
<chain base_link="panda_link0" tip_link="panda_hand" /> <chain base_link="panda_link0" tip_link="panda_hand" />
</group> </group>
<group name="hand"> <group name="hand">
<link name="panda_hand" /> <link name="panda_hand" />
...@@ -59,15 +59,6 @@ ...@@ -59,15 +59,6 @@
<joint name="panda_finger_joint2" /> <joint name="panda_finger_joint2" />
</group> </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 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"> <group_state name="ready" group="panda_arm">
<joint name="panda_joint1" value="0" /> <joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" /> <joint name="panda_joint2" value="-0.785" />
...@@ -77,15 +68,6 @@ ...@@ -77,15 +68,6 @@
<joint name="panda_joint6" value="1.571" /> <joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" /> <joint name="panda_joint7" value="0.785" />
</group_state> </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"> <group_state name="ready" group="panda_arm_hand">
<joint name="panda_joint1" value="0" /> <joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" /> <joint name="panda_joint2" value="-0.785" />
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment