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

Merge remote-tracking branch 'thomas_timm/master' into ur3_support

This commit is contained in:
Robot Printer
2015-10-28 10:06:31 +01:00
22 changed files with 996 additions and 307 deletions

View File

@@ -22,10 +22,10 @@ force_torque_sensor_controller:
type: force_torque_sensor_controller/ForceTorqueSensorController
publish_rate: 125
# Joint Trajectory Controller -------------------------------
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
velocity_based_position_trajectory_controller:
type: velocity_controllers/JointTrajectoryController
pos_based_pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
@@ -47,12 +47,49 @@ velocity_based_position_trajectory_controller:
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}
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}
# state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5
# Joint Trajectory Controller -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
vel_based_pos_traj_controller:
type: velocity_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
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:
#!!These values are useable, but maybe not optimal
shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
elbow_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_1_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_2_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_3_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
# state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20

View File

@@ -24,7 +24,7 @@ force_torque_sensor_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
position_based_position_trajectory_controller:
pos_based_pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
@@ -60,7 +60,7 @@ position_based_position_trajectory_controller:
# Joint Trajectory Controller - velocity based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
velocity_based_position_trajectory_controller:
vel_based_pos_traj_controller:
type: velocity_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
@@ -82,13 +82,13 @@ velocity_based_position_trajectory_controller:
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}
#!!These values are useable, but maybe not optimal
shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
elbow_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_1_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_2_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
wrist_3_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
# state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20