runtime/rasmt_support/config/rasmt_ros2_controllers.yaml
2022-01-24 19:10:30 +00:00

39 lines
No EOL
821 B
YAML

controller_manager:
ros__parameters:
update_rate: 100 # Hz
rasmt_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
rasmt_hand_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
rasmt_arm_controller:
ros__parameters:
command_interfaces:
- position
state_interfaces:
- position
- velocity
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
rasmt_hand_controller:
ros__parameters:
joints:
- rasmt_Slide_1
- rasmt_Slide_2
command_interfaces:
- position
state_interfaces:
- position
- velocity