quadruped_ros2_control/descriptions/quadruped_gazebo/config/robot_control.yaml

95 lines
1.7 KiB
YAML
Raw Normal View History

2024-09-09 22:18:19 +08:00
# Controller Manager configuration
controller_manager:
ros__parameters:
2024-09-19 22:45:08 +08:00
update_rate: 500 # Hz
2024-09-09 22:18:19 +08:00
# Define the available controllers
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
imu_sensor_broadcaster:
type: imu_sensor_broadcaster/IMUSensorBroadcaster
2024-09-19 22:45:08 +08:00
leg_pd_controller:
type: leg_pd_controller/LegPdController
unitree_guide_controller:
type: unitree_guide_controller/UnitreeGuideController
2024-09-09 22:18:19 +08:00
imu_sensor_broadcaster:
ros__parameters:
sensor_name: "imu_sensor"
2024-09-19 22:45:08 +08:00
frame_id: "imu_sensor"
leg_pd_controller:
ros__parameters:
joints:
- RF_HAA
- RF_HFE
2024-09-19 22:45:08 +08:00
- RF_KFE
- LF_HAA
- LF_HFE
- LF_KFE
- RH_HAA
- RH_HFE
- RH_KFE
- LH_HAA
- LH_HFE
- LH_KFE
command_interfaces:
- effort
state_interfaces:
- position
- velocity
unitree_guide_controller:
ros__parameters:
command_prefix: "leg_pd_controller"
2024-09-19 22:45:08 +08:00
joints:
- RF_HAA
- RF_HFE
2024-09-19 22:45:08 +08:00
- RF_KFE
- LF_HAA
- LF_HFE
- LF_KFE
- RH_HAA
- RH_HFE
- RH_KFE
- LH_HAA
- LH_HFE
- LH_KFE
command_interfaces:
- effort
2024-09-19 22:45:08 +08:00
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- RF_FOOT
- LF_FOOT
- RH_FOOT
- LH_FOOT
2024-09-19 22:45:08 +08:00
imu_name: "imu_sensor"
2024-09-20 17:56:00 +08:00
base_name: "base"
2024-09-19 22:45:08 +08:00
imu_interfaces:
- orientation.w
- orientation.x
- orientation.y
- orientation.z
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
- linear_acceleration.z