quadruped_ros2_control/descriptions/unitree/go2_description/config/robot_control.yaml

183 lines
3.5 KiB
YAML
Raw Normal View History

2024-09-09 22:18:19 +08:00
# Controller Manager configuration
controller_manager:
ros__parameters:
2024-10-10 21:22:58 +08:00
update_rate: 1000 # Hz
2024-09-09 22:18:19 +08:00
# Define the available controllers
joint_state_broadcaster:
2024-09-14 11:41:38 +08:00
type: joint_state_broadcaster/JointStateBroadcaster
imu_sensor_broadcaster:
type: imu_sensor_broadcaster/IMUSensorBroadcaster
2024-09-14 17:54:39 +08:00
unitree_guide_controller:
type: unitree_guide_controller/UnitreeGuideController
2024-09-25 21:01:50 +08:00
ocs2_quadruped_controller:
type: ocs2_quadruped_controller/Ocs2QuadrupedController
2024-10-10 21:22:58 +08:00
rl_quadruped_controller:
type: rl_quadruped_controller/LeggedGymController
2024-09-14 11:41:38 +08:00
imu_sensor_broadcaster:
ros__parameters:
sensor_name: "imu_sensor"
2024-09-14 17:54:39 +08:00
frame_id: "imu_link"
unitree_guide_controller:
ros__parameters:
2024-09-16 13:44:08 +08:00
update_rate: 500 # Hz
2024-09-14 17:54:39 +08:00
joints:
- 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
command_interfaces:
- effort
2024-09-14 17:54:39 +08:00
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
2024-09-16 13:44:08 +08:00
- velocity
feet_names:
2024-09-20 13:07:59 +08:00
- FR_foot
- FL_foot
- RR_foot
- RL_foot
2024-09-16 13:44:08 +08:00
imu_name: "imu_sensor"
2024-09-20 17:56:00 +08:00
base_name: "base"
2024-09-16 13:44:08 +08:00
imu_interfaces:
2024-09-17 14:03:08 +08:00
- orientation.w
2024-09-16 21:15:34 +08:00
- orientation.x
- orientation.y
- orientation.z
2024-09-16 13:44:08 +08:00
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
2024-09-25 21:01:50 +08:00
- linear_acceleration.z
ocs2_quadruped_controller:
ros__parameters:
2024-10-10 21:22:58 +08:00
update_rate: 100 # Hz
2024-09-25 21:01:50 +08:00
joints:
- FL_hip_joint
- FL_thigh_joint
- FL_calf_joint
- FR_hip_joint
- FR_thigh_joint
- FR_calf_joint
2024-09-29 17:09:06 +08:00
- RL_hip_joint
- RL_thigh_joint
- RL_calf_joint
2024-09-25 21:01:50 +08:00
- RR_hip_joint
- RR_thigh_joint
- RR_calf_joint
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet:
2024-09-25 21:01:50 +08:00
- FL_foot
- FR_foot
2024-09-29 17:09:06 +08:00
- RL_foot
2024-09-25 21:01:50 +08:00
- RR_foot
imu_name: "imu_sensor"
base_name: "base"
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
foot_force_name: "foot_force"
foot_force_interfaces:
- FL
- RL
- FR
2024-10-10 21:22:58 +08:00
- RR
rl_quadruped_controller:
ros__parameters:
update_rate: 200 # Hz
joints:
- FL_hip_joint
- FL_thigh_joint
- FL_calf_joint
- FR_hip_joint
- FR_thigh_joint
- FR_calf_joint
- RL_hip_joint
- RL_thigh_joint
- RL_calf_joint
- RR_hip_joint
- RR_thigh_joint
- RR_calf_joint
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
2024-10-15 22:40:15 +08:00
feet_names:
- FL_foot
- FR_foot
- RL_foot
- RR_foot
2024-10-10 21:22:58 +08:00
imu_name: "imu_sensor"
2024-10-15 22:40:15 +08:00
base_name: "base"
2024-10-10 21:22:58 +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