runtime/rasmt_support/config/rasmt_effort_controllers.yaml

80 lines
1.5 KiB
YAML
Raw Normal View History

2023-02-03 07:04:12 +00:00
controller_manager:
ros__parameters:
update_rate: 250
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
rasmt_arm_controller:
type: effort_controllers/JointGroupEffortController
rasmt_hand_controller:
type: effort_controllers/JointGroupEffortController
rasmt_arm_controller:
ros__parameters:
joints:
- rasmt_Rot_Z_1
- rasmt_Rot_Y_1
- rasmt_Rot_Z_2
- rasmt_Rot_Y_2
- rasmt_Rot_Z_3
- rasmt_Rot_Y_4
command_interfaces:
- effort
state_interfaces:
- position
- velocity
gains:
rasmt_Rot_Z_1:
p: 4000.0
d: 10.0
i: 250.0
i_clamp: 15.0
rasmt_Rot_Y_1:
p: 10000.0
d: 25.0
i: 600.0
i_clamp: 45.0
rasmt_Rot_Z_2:
p: 8000.0
d: 20.0
i: 450.0
i_clamp: 30.0
rasmt_Rot_Y_2:
p: 6000.0
d: 15.0
i: 300.0
i_clamp: 30.0
rasmt_Rot_Z_3:
p: 3000.0
d: 5.0
i: 175.0
i_clamp: 7.0
rasmt_Rot_Y_4:
p: 2500.0
d: 3.0
i: 150.0
i_clamp: 6.0
rasmt_hand_controller:
ros__parameters:
joints:
- rasmt_Slide_1
- rasmt_Slide_2
command_interfaces:
- effort
state_interfaces:
- position
- velocity
gains:
rasmt_Slide_1:
p: 225.0
d: 0.001
i: 0.4
i_clamp: 4.0
rasmt_Slide_2:
p: 225.0
d: 0.001
i: 0.4
i_clamp: 4.0