add rl for x30
This commit is contained in:
parent
f8a32f29db
commit
818211736e
|
@ -36,6 +36,13 @@ source ~/ros2_ws/install/setup.bash
|
||||||
ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=go2_description
|
ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=go2_description
|
||||||
```
|
```
|
||||||
|
|
||||||
|
### 3.2 Gazebo Classic 11 (ROS2 Humble)
|
||||||
|
```bash
|
||||||
|
source ~/ros2_ws/install/setup.bash
|
||||||
|
ros2 launch rl_quadruped_controller gazebo_classic.launch.py pkg_description:=a1_description
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
### 3.3 Gazebo Harmonic (ROS2 Jazzy)
|
### 3.3 Gazebo Harmonic (ROS2 Jazzy)
|
||||||
```bash
|
```bash
|
||||||
source ~/ros2_ws/install/setup.bash
|
source ~/ros2_ws/install/setup.bash
|
||||||
|
|
|
@ -34,6 +34,12 @@ ros2 launch x30_description visualize.launch.py
|
||||||
source ~/ros2_ws/install/setup.bash
|
source ~/ros2_ws/install/setup.bash
|
||||||
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=x30_description
|
ros2 launch ocs2_quadruped_controller mujoco.launch.py pkg_description:=x30_description
|
||||||
```
|
```
|
||||||
|
* RL Quadruped Controller
|
||||||
|
```bash
|
||||||
|
source ~/ros2_ws/install/setup.bash
|
||||||
|
ros2 launch rl_quadruped_controller mujoco.launch.py pkg_description:=x30_description model_folder:=legged_gym
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
### Gazebo Classic 11 (ROS2 Humble)
|
### Gazebo Classic 11 (ROS2 Humble)
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,41 @@
|
||||||
|
model_name: "policy.pt"
|
||||||
|
framework: "isaacgym"
|
||||||
|
rows: 4
|
||||||
|
cols: 3
|
||||||
|
decimation: 4
|
||||||
|
num_observations: 48
|
||||||
|
observations: ["lin_vel", "ang_vel", "gravity_vec", "commands", "dof_pos", "dof_vel", "actions"]
|
||||||
|
#observations_history: [6, 5, 4, 3, 2, 1, 0]
|
||||||
|
clip_obs: 100.0
|
||||||
|
clip_actions_lower: [-100, -100, -100,
|
||||||
|
-100, -100, -100,
|
||||||
|
-100, -100, -100,
|
||||||
|
-100, -100, -100]
|
||||||
|
clip_actions_upper: [100, 100, 100,
|
||||||
|
100, 100, 100,
|
||||||
|
100, 100, 100,
|
||||||
|
100, 100, 100]
|
||||||
|
rl_kp: [160, 160, 160,
|
||||||
|
160, 160, 160,
|
||||||
|
160, 160, 160,
|
||||||
|
160, 160, 160,]
|
||||||
|
rl_kd: [8.0, 8.0, 8.0,
|
||||||
|
8.0, 8.0, 8.0,
|
||||||
|
8.0, 8.0, 8.0,
|
||||||
|
8.0, 8.0, 8.0]
|
||||||
|
hip_scale_reduction: 1.0
|
||||||
|
hip_scale_reduction_indices: [0, 3, 6, 9]
|
||||||
|
num_of_dofs: 12
|
||||||
|
action_scale: 0.25
|
||||||
|
|
||||||
|
lin_vel_scale: 2.0
|
||||||
|
ang_vel_scale: 0.25
|
||||||
|
dof_pos_scale: 1.0
|
||||||
|
dof_vel_scale: 0.05
|
||||||
|
|
||||||
|
commands_scale: [2.0, 2.0, 0.25]
|
||||||
|
|
||||||
|
torque_limits: [33.5, 33.5, 33.5,
|
||||||
|
33.5, 33.5, 33.5,
|
||||||
|
33.5, 33.5, 33.5,
|
||||||
|
33.5, 33.5, 33.5]
|
Binary file not shown.
|
@ -164,3 +164,92 @@ ocs2_quadruped_controller:
|
||||||
- HL
|
- HL
|
||||||
- FR
|
- FR
|
||||||
- HR
|
- HR
|
||||||
|
|
||||||
|
rl_quadruped_controller:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 200 # Hz
|
||||||
|
robot_pkg: "x30_description"
|
||||||
|
model_folder: "legged_gym"
|
||||||
|
stand_kp: 500.0
|
||||||
|
stand_kd: 20.0
|
||||||
|
joints:
|
||||||
|
- FL_HipX
|
||||||
|
- FL_HipY
|
||||||
|
- FL_Knee
|
||||||
|
- FR_HipX
|
||||||
|
- FR_HipY
|
||||||
|
- FR_Knee
|
||||||
|
- HL_HipX
|
||||||
|
- HL_HipY
|
||||||
|
- HL_Knee
|
||||||
|
- HR_HipX
|
||||||
|
- HR_HipY
|
||||||
|
- HR_Knee
|
||||||
|
|
||||||
|
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
|
||||||
|
|
||||||
|
command_interfaces:
|
||||||
|
- effort
|
||||||
|
- position
|
||||||
|
- velocity
|
||||||
|
- kp
|
||||||
|
- kd
|
||||||
|
|
||||||
|
state_interfaces:
|
||||||
|
- effort
|
||||||
|
- position
|
||||||
|
- velocity
|
||||||
|
|
||||||
|
feet_names:
|
||||||
|
- FL_FOOT
|
||||||
|
- FR_FOOT
|
||||||
|
- HL_FOOT
|
||||||
|
- HR_FOOT
|
||||||
|
|
||||||
|
foot_force_name: "foot_force"
|
||||||
|
foot_force_interfaces:
|
||||||
|
- FL
|
||||||
|
- FR
|
||||||
|
- HL
|
||||||
|
- HR
|
||||||
|
|
||||||
|
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
|
Loading…
Reference in New Issue