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

Included a position-based controller. Also prettied up printing

This commit is contained in:
Thomas Timm Andersen
2015-09-25 09:57:33 +02:00
parent a15fcc695c
commit 5c785af6c4
14 changed files with 299 additions and 242 deletions

View File

@@ -22,7 +22,43 @@ 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
position_based_position_trajectory_controller:
type: position_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 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}
# 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 - velocity based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
velocity_based_position_trajectory_controller:
type: velocity_controllers/JointTrajectoryController