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

236 lines
4.3 KiB
YAML

# Controller Manager configuration
controller_manager:
ros__parameters:
update_rate: 1000 # Hz
# 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
ocs2_quadruped_controller:
type: ocs2_quadruped_controller/Ocs2QuadrupedController
rl_quadruped_controller:
type: rl_quadruped_controller/LeggedGymController
imu_sensor_broadcaster:
ros__parameters:
sensor_name: "imu_sensor"
frame_id: "imu_link"
unitree_guide_controller:
ros__parameters:
update_rate: 200 # Hz
down_pos:
- -0.01
- 1.27
- -2.8
- 0.01
- 1.27
- -2.8
- -0.3
- 1.31
- -2.8
- 0.3
- 1.31
- -2.8
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
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- FR_foot
- FL_foot
- RR_foot
- RL_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
ocs2_quadruped_controller:
ros__parameters:
update_rate: 500 # Hz
robot_pkg: "go2_description"
feet_force_threshold: 20.0
# default_kd: 3.5
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
feet:
- FL_foot
- FR_foot
- RL_foot
- 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
- RR
rl_quadruped_controller:
ros__parameters:
update_rate: 200 # Hz
robot_pkg: "go2_description"
# use_rl_thread: false
model_folder: "himloco"
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
stand_pos:
- 0.1000
- 0.8000
- -1.5000
- -0.1000
- 0.8000
- -1.5000
- 0.1000
- 0.8000
- -1.5000
- -0.1000
- 0.8000
- -1.5000
down_pos:
- 0.01
- 1.27
- -2.8
- -0.01
- 1.27
- -2.8
- 0.3
- 1.31
- -2.8
- -0.3
- 1.31
- -2.8
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet_names:
- FL_foot
- FR_foot
- RL_foot
- RR_foot
foot_force_name: "foot_force"
foot_force_interfaces:
- FL
- FR
- RL
- RR
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