1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +02:00

Added control switching

This commit is contained in:
Thomas Timm Andersen
2015-09-24 13:50:53 +02:00
parent af601b9c32
commit 1e8f13f232
7 changed files with 73 additions and 25 deletions

View File

@@ -33,7 +33,7 @@ position_trajectory_controller:
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
@@ -42,14 +42,19 @@ position_trajectory_controller:
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 125
action_monitor_rate: 10
# gains:
# joint1: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
# joint2: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
stop_trajectory_duration: 0.5
state_publish_rate: 125
action_monitor_rate: 10
gains:
#!!These values have not been optimized!!
shoulder_pan_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
shoulder_lift_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
elbow_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_1_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_2_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_3_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
# state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5
# state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5

View File

@@ -47,12 +47,12 @@ position_trajectory_controller:
action_monitor_rate: 10
gains:
#!!These values have not been optimized!!
shoulder_pan_joint: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
shoulder_lift_joint: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
elbow_joint: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
wrist_1_joint: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
wrist_2_joint: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
wrist_3_joint: {p: 2.0, i: 0.0, d: 0.01, i_clamp: 1}
shoulder_pan_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
shoulder_lift_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
elbow_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_1_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_2_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_3_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
# state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20