quadruped_ros2_control/descriptions/deep_robotics/lite3_description/config/gazebo.yaml

165 lines
3.0 KiB
YAML
Raw Normal View History

2024-10-09 21:17:45 +08:00
# Controller Manager configuration
controller_manager:
ros__parameters:
update_rate: 1000 # Hz
2024-10-09 21:17:45 +08:00
# Define the available controllers
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
imu_sensor_broadcaster:
type: imu_sensor_broadcaster/IMUSensorBroadcaster
unitree_guide_controller:
type: unitree_guide_controller/UnitreeGuideController
2025-03-01 22:08:59 +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-10-09 21:17:45 +08:00
imu_sensor_broadcaster:
ros__parameters:
sensor_name: "imu_sensor"
frame_id: "imu_link"
2025-03-24 01:01:36 +08:00
update_rate: 200
2024-10-09 21:17:45 +08:00
2025-03-01 22:08:59 +08:00
ocs2_quadruped_controller:
2024-10-09 21:17:45 +08:00
ros__parameters:
2025-03-01 22:08:59 +08:00
update_rate: 200 # Hz
robot_pkg: "lite3_description"
default_kd: 2.0
2024-10-09 21:17:45 +08:00
joints:
- FL_HipX
- FL_HipY
- FL_Knee
2025-03-01 22:08:59 +08:00
- FR_HipX
- FR_HipY
- FR_Knee
2024-10-09 21:17:45 +08:00
- HL_HipX
- HL_HipY
- HL_Knee
2025-03-01 22:08:59 +08:00
- HR_HipX
- HR_HipY
- HR_Knee
2024-10-09 21:17:45 +08:00
command_interfaces:
- effort
2025-03-01 22:08:59 +08:00
- position
- velocity
- kp
- kd
2024-10-09 21:17:45 +08:00
state_interfaces:
2025-03-01 22:08:59 +08:00
- effort
2024-10-09 21:17:45 +08:00
- position
- velocity
2025-03-01 22:08:59 +08:00
feet:
- FL_FOOT
- FR_FOOT
- HL_FOOT
- HR_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
# estimator_type: "odom"
foot_force_name: "foot_force"
foot_force_interfaces:
- FL_foot_force
- HL_foot_force
- FR_foot_force
- HR_foot_force
2024-10-09 21:17:45 +08:00
unitree_guide_controller:
ros__parameters:
update_rate: 200 # Hz
# stand_kp: 30.0
stand_kd: 1.0
2024-10-09 21:17:45 +08:00
joints:
- FR_HipX
- FR_HipY
- FR_Knee
- FL_HipX
- FL_HipY
- FL_Knee
- HR_HipX
- HR_HipY
- HR_Knee
- HL_HipX
- HL_HipY
- HL_Knee
2024-10-21 21:47:25 +08:00
down_pos:
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
- 0.0
- -1.22
- 2.61
stand_pos:
- 0.0
- -0.732
- 1.361
- 0.0
- -0.732
- 1.361
- 0.0
- -0.732
- 1.361
- 0.0
- -0.732
- 1.361
2024-10-09 21:17:45 +08:00
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- FR_FOOT
- FL_FOOT
- HR_FOOT
- HL_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