2024-09-09 22:18:19 +08:00
|
|
|
# Controller Manager configuration
|
|
|
|
controller_manager:
|
|
|
|
ros__parameters:
|
2024-10-10 22:44:32 +08:00
|
|
|
update_rate: 2000 # 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
|
|
|
|
|
2024-09-20 12:48:45 +08:00
|
|
|
unitree_guide_controller:
|
|
|
|
type: unitree_guide_controller/UnitreeGuideController
|
|
|
|
|
2024-10-10 22:44:32 +08:00
|
|
|
rl_quadruped_controller:
|
|
|
|
type: rl_quadruped_controller/LeggedGymController
|
|
|
|
|
2024-09-09 22:18:19 +08:00
|
|
|
imu_sensor_broadcaster:
|
|
|
|
ros__parameters:
|
|
|
|
sensor_name: "imu_sensor"
|
2024-10-10 22:44:32 +08:00
|
|
|
frame_id: "imu_link"
|
2024-09-19 22:45:08 +08:00
|
|
|
|
|
|
|
leg_pd_controller:
|
|
|
|
ros__parameters:
|
|
|
|
joints:
|
2024-10-10 22:44:32 +08:00
|
|
|
- FR_hip_joint
|
|
|
|
- FR_thigh_joint
|
|
|
|
- FR_calf_joint
|
|
|
|
- FL_hip_joint
|
|
|
|
- FL_thigh_joint
|
|
|
|
- FL_calf_joint
|
|
|
|
- RR_hip_joint
|
|
|
|
- RR_thigh_joint
|
|
|
|
- RR_calf_joint
|
|
|
|
- RL_hip_joint
|
|
|
|
- RL_thigh_joint
|
|
|
|
- RL_calf_joint
|
2024-09-19 22:45:08 +08:00
|
|
|
|
|
|
|
command_interfaces:
|
|
|
|
- effort
|
|
|
|
|
|
|
|
state_interfaces:
|
|
|
|
- position
|
|
|
|
- velocity
|
|
|
|
|
|
|
|
unitree_guide_controller:
|
|
|
|
ros__parameters:
|
2024-09-20 12:48:45 +08:00
|
|
|
command_prefix: "leg_pd_controller"
|
2024-10-10 22:44:32 +08:00
|
|
|
update_rate: 500 # Hz
|
2024-10-21 21:47:25 +08:00
|
|
|
stand_kp: 100.0
|
|
|
|
stand_kd: 8.0
|
2024-09-19 22:45:08 +08:00
|
|
|
joints:
|
2024-10-10 22:44:32 +08:00
|
|
|
- FR_hip_joint
|
|
|
|
- FR_thigh_joint
|
|
|
|
- FR_calf_joint
|
|
|
|
- FL_hip_joint
|
|
|
|
- FL_thigh_joint
|
|
|
|
- FL_calf_joint
|
|
|
|
- RR_hip_joint
|
|
|
|
- RR_thigh_joint
|
|
|
|
- RR_calf_joint
|
|
|
|
- RL_hip_joint
|
|
|
|
- RL_thigh_joint
|
|
|
|
- RL_calf_joint
|
2024-09-19 22:45:08 +08:00
|
|
|
|
|
|
|
command_interfaces:
|
2024-09-20 12:48:45 +08:00
|
|
|
- effort
|
2024-09-19 22:45:08 +08:00
|
|
|
- position
|
|
|
|
- velocity
|
|
|
|
- kp
|
|
|
|
- kd
|
|
|
|
|
|
|
|
state_interfaces:
|
|
|
|
- effort
|
|
|
|
- position
|
|
|
|
- velocity
|
|
|
|
|
2024-09-20 12:48:45 +08:00
|
|
|
feet_names:
|
2024-10-10 22:44:32 +08:00
|
|
|
- FR_foot
|
|
|
|
- FL_foot
|
|
|
|
- RR_foot
|
|
|
|
- RL_foot
|
2024-09-20 12:48:45 +08:00
|
|
|
|
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
|