feat: [Breaking change] split config.yaml into separate model folders

This commit is contained in:
fan-ziqi 2024-08-15 23:14:48 +08:00
parent e42d926bf3
commit 4540198171
27 changed files with 314 additions and 301 deletions

View File

@ -71,6 +71,8 @@ cd ..
catkin build
```
If catkin build report errors: `Unable to find either executable 'empy' or Python module 'em'`, run `catkin config -DPYTHON_EXECUTABLE=/usr/bin/python3` before `catkin build`
## Running
Before running, copy the trained pt model file to `rl_sar/src/rl_sar/models/YOUR_ROBOT_NAME`, and configure the parameters in `config.yaml`.
@ -100,9 +102,9 @@ Control:
* Press **\<Space\>** to sets all control commands to zero.
* If robot falls down, press **R** to reset Gazebo environment.
### Physical Robots
### Real Robots
#### Unitree A1
**Example: Unitree A1**
Unitree A1 can be connected using both wireless and wired methods:
@ -135,14 +137,13 @@ Or press **0** on the keyboard to switch the robot to the default standing posit
## Add Your Robot
In the following, let ROBOT represent the name of your robot.
In the following text, `<ROBOT>` represents the name of the robot
1. Create a model package named ROBOT_description in the robots folder. Place the URDF model in the urdf path within the folder and name it ROBOT.urdf. Create a namespace named ROBOT_gazebo in the config folder within the model file for joint configuration.
2. Place the model file in models/ROBOT.
3. Add a new field in rl_sar/config.yaml named ROBOT and adjust the parameters, such as changing the model_name to the model file name from the previous step.
4. Add a new launch file in the rl_sar/launch folder. Refer to other launch files for guidance on modification.
5. Change ROBOT_NAME to ROBOT in rl_xxx.cpp.
6. Compile and run.
1. Create a model package named `<ROBOT>_description` in the `rl_sar/src/robots` directory. Place the robot's URDF file in the `rl_sar/src/robots/<ROBOT>_description/urdf` directory and name it `<ROBOT>.urdf`. Additionally, create a joint configuration file with the namespace `<ROBOT>_gazebo` in the `rl_sar/src/robots/<ROBOT>_description/config` directory.
2. Place the trained RL model files in the `rl_sar/src/rl_sar/models/<ROBOT>` directory.
3. In the `rl_sar/src/rl_sar/models/<ROBOT>` directory, create a `config.yaml` file, and modify its parameters based on the `rl_sar/src/rl_sar/models/a1_isaacgym/config.yaml` file.
4. If you need to run simulations, modify the launch files as needed by referring to those in the `rl_sar/src/rl_sar/launch` directory.
5. If you need to run on the physical robot, modify the file `rl_sar/src/rl_sar/src/rl_real_a1.cpp` as needed.
## Reference

View File

@ -71,6 +71,8 @@ cd ..
catkin build
```
如果 catkin build 报错: `Unable to find either executable 'empy' or Python module 'em'`, 在`catkin build` 之前执行 `catkin config -DPYTHON_EXECUTABLE=/usr/bin/python3`
## 运行
运行前请将训练好的pt模型文件拷贝到`rl_sar/src/rl_sar/models/YOUR_ROBOT_NAME`中,并配置`config.yaml`中的参数。
@ -101,9 +103,9 @@ source devel/setup.bash
* 按 **\<Space\>** 将所有控制指令设置为零。
* 如果机器人摔倒,按 **R** 重置Gazebo环境。
### 实物
### 真实机器人
#### Unitree A1
**示例Unitree A1**
与Unitree A1连接可以使用无线与有线两种方式
@ -136,14 +138,13 @@ rosrun rl_sar rl_real_a1
## 添加你的机器人
下文中将ROBOT代表机器人名称
下文中将`<ROBOT>`代表机器人名称
1. 在robots文件夹中创建名为ROBOT_description的模型包将模型的urdf放到文件夹中的urdf路径下并命名为ROBOT.urdf在模型文件中的config文件夹中创建命名空间为ROBOT_gazebo的关节配置文件
2. 将模型文件放到models/ROBOT中
3. 在rl_sar/config.yaml中添加一个新的字段命名为ROBOT更改其中参数如将model_name改为上一步的模型文件名
4. 在rl_sar/launch文件夹中添加一个新的launch文件请参考其他launch文件自行修改
5. 修改rl_xxx.cpp中的ROBOT_NAME为ROBOT
6. 编译运行
1. 在`rl_sar/src/robots`路径下创建名为`<ROBOT>_description`的模型包将模型的urdf放到`rl_sar/src/robots/<ROBOT>_description/urdf`路径下并命名为`<ROBOT>.urdf`,并在`rl_sar/src/robots/<ROBOT>_description/config`路径下创建命名空间为`<ROBOT>_gazebo`的关节配置文件
2. 将训练好的RL模型文件放到`rl_sar/src/rl_sar/models/<ROBOT>`路径下
3. 在`rl_sar/src/rl_sar/models/<ROBOT>`中新建config.yaml文件参考`rl_sar/src/rl_sar/models/a1_isaacgym/config.yaml`文件修改其中参数
4. 若需要运行仿真,则参考`rl_sar/src/rl_sar/launch`路径下的launch文件自行修改
5. 若需要运行实物,则参考`rl_sar/src/rl_sar/src/rl_real_a1.cpp`文件自行修改
## 参考

View File

@ -1,257 +0,0 @@
a1:
model_name: "model_0702.pt"
framework: "isaacgym"
rows: 4
cols: 3
dt: 0.005
decimation: 4
num_observations: 45
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: [20, 20, 20,
20, 20, 20,
20, 20, 20,
20, 20, 20]
rl_kd: [0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5]
fixed_kp: [80, 80, 80,
80, 80, 80,
80, 80, 80,
80, 80, 80]
fixed_kd: [3, 3, 3,
3, 3, 3,
3, 3, 3,
3, 3, 3]
hip_scale_reduction: 0.5
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, 1.0]
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]
default_dof_pos: [ 0.1000, 0.8000, -1.5000,
-0.1000, 0.8000, -1.5000,
0.1000, 1.0000, -1.5000,
-0.1000, 1.0000, -1.5000]
joint_controller_names: ["FL_hip_controller", "FL_thigh_controller", "FL_calf_controller",
"FR_hip_controller", "FR_thigh_controller", "FR_calf_controller",
"RL_hip_controller", "RL_thigh_controller", "RL_calf_controller",
"RR_hip_controller", "RR_thigh_controller", "RR_calf_controller"]
gr1t1:
model_name: "model_4000_jit.pt"
framework: "isaacgym"
rows: 2
cols: 5
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]
gr1t2:
model_name: "model_4000_jit.pt"
framework: "isaacgym"
rows: 2
cols: 5
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]
a1_isaaclab:
model_name: "policy.pt"
framework: "isaacsim"
rows: 4
cols: 3
dt: 0.005
decimation: 4
num_observations: 45
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: [20, 20, 20,
20, 20, 20,
20, 20, 20,
20, 20, 20]
rl_kd: [0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5]
fixed_kp: [80, 80, 80,
80, 80, 80,
80, 80, 80,
80, 80, 80]
fixed_kd: [3, 3, 3,
3, 3, 3,
3, 3, 3,
3, 3, 3]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
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: [1.0, 1.0, 1.0]
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]
default_dof_pos: [ 0.1000, 0.8000, -1.5000,
-0.1000, 0.8000, -1.5000,
0.1000, 1.0000, -1.5000,
-0.1000, 1.0000, -1.5000]
joint_controller_names: ["FL_hip_controller", "FL_thigh_controller", "FL_calf_controller",
"FR_hip_controller", "FR_thigh_controller", "FR_calf_controller",
"RL_hip_controller", "RL_thigh_controller", "RL_calf_controller",
"RR_hip_controller", "RR_thigh_controller", "RR_calf_controller"]
gr1t1_isaaclab:
model_name: "policy.pt"
framework: "isaacsim"
rows: 2
cols: 5
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]
gr1t2_isaaclab:
model_name: "policy.pt"
framework: "isaacsim"
rows: 2
cols: 5
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]

View File

@ -31,7 +31,6 @@ private:
void RobotControl();
// history buffer
bool use_history = true;
ObservationBuffer history_obs_buf;
torch::Tensor history_obs;
@ -65,6 +64,7 @@ private:
void CmdvelCallback(const geometry_msgs::Twist::ConstPtr &msg);
// others
std::string gazebo_model_name;
int motiontime = 0;
std::map<std::string, size_t> sorted_to_original_index;
std::vector<double> mapped_joint_positions;

View File

@ -1,9 +1,9 @@
<launch>
<arg name="wname" default="stairs"/>
<arg name="rname" default="a1"/>
<param name="robot_name" type="str" value="$(arg rname)_isaaclab"/>
<param name="use_history" type="bool" value="false"/>
<param name="robot_name" type="str" value="$(arg rname)_isaacgym"/>
<param name="ros_namespace" type="str" value="/$(arg rname)_gazebo/"/>
<param name="gazebo_model_name" type="str" value="$(arg rname)_gazebo"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>

View File

@ -1,9 +1,9 @@
<launch>
<arg name="wname" default="stairs"/>
<arg name="rname" default="a1"/>
<param name="robot_name" type="str" value="$(arg rname)"/>
<param name="use_history" type="bool" value="true"/>
<param name="robot_name" type="str" value="$(arg rname)_isaacsim"/>
<param name="ros_namespace" type="str" value="/$(arg rname)_gazebo/"/>
<param name="gazebo_model_name" type="str" value="$(arg rname)_gazebo"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>

View File

@ -1,9 +1,9 @@
<launch>
<arg name="wname" default="stairs"/>
<arg name="rname" default="gr1t1"/>
<param name="robot_name" type="str" value="$(arg rname)"/>
<param name="use_history" type="bool" value="false"/>
<param name="robot_name" type="str" value="$(arg rname)_isaacgym"/>
<param name="ros_namespace" type="str" value="/$(arg rname)_gazebo/"/>
<param name="gazebo_model_name" type="str" value="$(arg rname)_gazebo"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>

View File

@ -1,9 +1,9 @@
<launch>
<arg name="wname" default="stairs"/>
<arg name="rname" default="gr1t2"/>
<param name="robot_name" type="str" value="$(arg rname)"/>
<param name="use_history" type="bool" value="false"/>
<param name="robot_name" type="str" value="$(arg rname)_isaacgym"/>
<param name="ros_namespace" type="str" value="/$(arg rname)_gazebo/"/>
<param name="gazebo_model_name" type="str" value="$(arg rname)_gazebo"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>

View File

@ -340,18 +340,24 @@ std::vector<T> ReadVectorFromYaml(const YAML::Node& node, const std::string& fra
{
return values;
}
else
{
throw std::invalid_argument("Unsupported framework: " + framework);
}
}
void RL::ReadYaml(std::string robot_name)
{
// The config file is located at "rl_sar/src/rl_sar/models/<robot_name>/config.yaml"
std::string config_path = std::string(CMAKE_CURRENT_SOURCE_DIR) + "/models/" + robot_name + "/config.yaml";
YAML::Node config;
try
{
config = YAML::LoadFile(CONFIG_PATH)[robot_name];
config = YAML::LoadFile(config_path)[robot_name];
} catch(YAML::BadFile &e)
{
std::cout << LOGGER::ERROR << "The file '" << CONFIG_PATH << "' does not exist" << std::endl;
std::cout << LOGGER::ERROR << "The file '" << config_path << "' does not exist" << std::endl;
return;
}
@ -359,6 +365,7 @@ void RL::ReadYaml(std::string robot_name)
this->params.framework = config["framework"].as<std::string>();
int rows = config["rows"].as<int>();
int cols = config["cols"].as<int>();
this->params.use_history = config["use_history"].as<bool>();
this->params.dt = config["dt"].as<double>();
this->params.decimation = config["decimation"].as<int>();
this->params.num_observations = config["num_observations"].as<int>();

View File

@ -7,7 +7,6 @@
#include <unistd.h>
#include <yaml-cpp/yaml.h>
#define CONFIG_PATH CMAKE_CURRENT_SOURCE_DIR "/config.yaml"
namespace LOGGER {
const char* const INFO = "\033[0;37m[INFO]\033[0m ";
@ -71,6 +70,7 @@ struct ModelParams
{
std::string model_name;
std::string framework;
bool use_history;
double dt;
int decimation;
int num_observations;

View File

@ -0,0 +1,55 @@
a1_isaacgym:
model_name: "model_0702.pt"
framework: "isaacgym"
rows: 4
cols: 3
use_history: True
dt: 0.005
decimation: 4
num_observations: 45
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: [20, 20, 20,
20, 20, 20,
20, 20, 20,
20, 20, 20]
rl_kd: [0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5]
fixed_kp: [80, 80, 80,
80, 80, 80,
80, 80, 80,
80, 80, 80]
fixed_kd: [3, 3, 3,
3, 3, 3,
3, 3, 3,
3, 3, 3]
hip_scale_reduction: 0.5
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, 1.0]
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]
default_dof_pos: [ 0.1000, 0.8000, -1.5000,
-0.1000, 0.8000, -1.5000,
0.1000, 1.0000, -1.5000,
-0.1000, 1.0000, -1.5000]
joint_controller_names: ["FL_hip_controller", "FL_thigh_controller", "FL_calf_controller",
"FR_hip_controller", "FR_thigh_controller", "FR_calf_controller",
"RL_hip_controller", "RL_thigh_controller", "RL_calf_controller",
"RR_hip_controller", "RR_thigh_controller", "RR_calf_controller"]

View File

@ -0,0 +1,55 @@
a1_isaacsim:
model_name: "policy.pt"
framework: "isaacsim"
rows: 4
cols: 3
use_history: False
dt: 0.005
decimation: 4
num_observations: 45
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: [20, 20, 20,
20, 20, 20,
20, 20, 20,
20, 20, 20]
rl_kd: [0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5,
0.5, 0.5, 0.5]
fixed_kp: [80, 80, 80,
80, 80, 80,
80, 80, 80,
80, 80, 80]
fixed_kd: [3, 3, 3,
3, 3, 3,
3, 3, 3,
3, 3, 3]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
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: [1.0, 1.0, 1.0]
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]
default_dof_pos: [ 0.1000, 0.8000, -1.5000,
-0.1000, 0.8000, -1.5000,
0.1000, 1.0000, -1.5000,
-0.1000, 1.0000, -1.5000]
joint_controller_names: ["FL_hip_controller", "FL_thigh_controller", "FL_calf_controller",
"FR_hip_controller", "FR_thigh_controller", "FR_calf_controller",
"RL_hip_controller", "RL_thigh_controller", "RL_calf_controller",
"RR_hip_controller", "RR_thigh_controller", "RR_calf_controller"]

View File

@ -0,0 +1,37 @@
gr1t1_isaacgym:
model_name: "model_4000_jit.pt"
framework: "isaacgym"
rows: 2
cols: 5
use_history: False
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]

View File

@ -0,0 +1,37 @@
gr1t1_isaacsim:
model_name: "policy.pt"
framework: "isaacsim"
rows: 2
cols: 5
use_history: False
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]

View File

@ -0,0 +1,37 @@
gr1t2_isaacgym:
model_name: "model_4000_jit.pt"
framework: "isaacgym"
rows: 2
cols: 5
use_history: False
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]

View File

@ -0,0 +1,37 @@
gr1t2_isaacsim:
model_name: "policy.pt"
framework: "isaacsim"
rows: 2
cols: 5
use_history: False
dt: 0.001
decimation: 20
num_observations: 39
clip_obs: 100.0
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3,
57.0, 43.0, 114.0, 114.0, 15.3]
fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5,
5.7, 4.3, 11.4, 11.4, 1.5]
hip_scale_reduction: 1.0
hip_scale_reduction_indices: []
num_of_dofs: 10
action_scale: 1.0
lin_vel_scale: 1.0
ang_vel_scale: 1.0
dof_pos_scale: 1.0
dof_vel_scale: 1.0
commands_scale: [1.0, 1.0, 1.0]
torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0,
60.0, 45.0, 130.0, 130.0, 16.0]
default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618,
0.0, 0.0, -0.2618, 0.5236, -0.2618]
joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller",
"r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"]

View File

@ -6,7 +6,6 @@ from pynput import keyboard
from enum import Enum, auto
BASE_PATH = os.path.join(os.path.dirname(__file__), "../")
CONFIG_PATH = os.path.join(BASE_PATH, "config.yaml")
class LOGGER:
INFO = "\033[0;37m[INFO]\033[0m "
@ -65,6 +64,7 @@ class ModelParams:
def __init__(self):
self.model_name = None
self.framework = None
self.use_history = None
self.dt = None
self.decimation = None
self.num_observations = None
@ -338,19 +338,24 @@ class RL:
return transposed_values
elif framework == "isaacgym":
return values
else:
raise ValueError(f"Unsupported framework: {framework}")
def ReadYaml(self, robot_name):
# The config file is located at "rl_sar/src/rl_sar/models/<robot_name>/config.yaml"
config_path = os.path.join(BASE_PATH, "models", robot_name, "config.yaml")
try:
with open(CONFIG_PATH, 'r') as f:
with open(config_path, 'r') as f:
config = yaml.safe_load(f)[robot_name]
except FileNotFoundError as e:
print(LOGGER.ERROR + "The file '{CONFIG_PATH}' does not exist")
print(LOGGER.ERROR + f"The file '{config_path}' does not exist")
return
self.params.model_name = config["model_name"]
self.params.framework = config["framework"]
rows = config["rows"]
cols = config["cols"]
self.params.use_history = config["use_history"]
self.params.dt = config["dt"]
self.params.decimation = config["decimation"]
self.params.num_observations = config["num_observations"]

View File

@ -36,8 +36,7 @@ class RL_Sim(RL):
self.ReadYaml(self.robot_name)
# history
self.use_history = rospy.get_param("use_history", "")
if self.use_history:
if self.params.use_history:
self.history_obs_buf = ObservationBuffer(1, self.params.num_observations, 6)
# Due to the fact that the robot_state_publisher sorts the joint names alphabetically,
@ -75,6 +74,7 @@ class RL_Sim(RL):
self.joint_state_subscriber = rospy.Subscriber(joint_states_topic, JointState, self.JointStatesCallback, queue_size=10)
# service
self.gazebo_model_name = rospy.get_param("gazebo_model_name", "")
self.gazebo_set_model_state_client = rospy.ServiceProxy("/gazebo/set_model_state", SetModelState)
self.gazebo_pause_physics_client = rospy.ServiceProxy("/gazebo/pause_physics", Empty)
self.gazebo_unpause_physics_client = rospy.ServiceProxy("/gazebo/unpause_physics", Empty)
@ -135,8 +135,7 @@ class RL_Sim(RL):
def RobotControl(self):
if self.control.control_state == STATE.STATE_RESET_SIMULATION:
set_model_state = SetModelStateRequest().model_state
gazebo_model_name = f"{self.robot_name}_gazebo"
set_model_state.model_name = gazebo_model_name
set_model_state.model_name = self.gazebo_model_name
set_model_state.pose.position.z = 1.0
set_model_state.reference_frame = "world"
self.gazebo_set_model_state_client(set_model_state)
@ -217,7 +216,7 @@ class RL_Sim(RL):
def Forward(self):
torch.set_grad_enabled(False)
clamped_obs = self.ComputeObservation()
if self.use_history:
if self.params.use_history:
self.history_obs_buf.insert(clamped_obs)
history_obs = self.history_obs_buf.get_obs_vec(np.arange(6))
actions = self.model.forward(history_obs)

View File

@ -8,7 +8,7 @@ RL_Real rl_sar;
RL_Real::RL_Real() : unitree_safe(UNITREE_LEGGED_SDK::LeggedType::A1), unitree_udp(UNITREE_LEGGED_SDK::LOWLEVEL)
{
// read params from yaml
this->robot_name = "a1";
this->robot_name = "a1_isaacgym";
this->ReadYaml(this->robot_name);
// history

View File

@ -12,8 +12,7 @@ RL_Sim::RL_Sim()
this->ReadYaml(this->robot_name);
// history
nh.param<bool>("use_history", this->use_history, "");
if(this->use_history)
if(this->params.use_history)
{
this->history_obs_buf = ObservationBuffer(1, this->params.num_observations, 6);
}
@ -56,6 +55,7 @@ RL_Sim::RL_Sim()
this->joint_state_subscriber = nh.subscribe<sensor_msgs::JointState>(this->ros_namespace + "joint_states", 10, &RL_Sim::JointStatesCallback, this);
// service
nh.param<std::string>("gazebo_model_name", this->gazebo_model_name, "");
this->gazebo_set_model_state_client = nh.serviceClient<gazebo_msgs::SetModelState>("/gazebo/set_model_state");
this->gazebo_pause_physics_client = nh.serviceClient<std_srvs::Empty>("/gazebo/pause_physics");
this->gazebo_unpause_physics_client = nh.serviceClient<std_srvs::Empty>("/gazebo/unpause_physics");
@ -150,8 +150,7 @@ void RL_Sim::RobotControl()
if(this->control.control_state == STATE_RESET_SIMULATION)
{
gazebo_msgs::SetModelState set_model_state;
std::string gazebo_model_name = this->robot_name + "_gazebo";
set_model_state.request.model_state.model_name = gazebo_model_name;
set_model_state.request.model_state.model_name = this->gazebo_model_name;
set_model_state.request.model_state.pose.position.z = 1.0;
set_model_state.request.model_state.reference_frame = "world";
this->gazebo_set_model_state_client.call(set_model_state);
@ -265,7 +264,7 @@ torch::Tensor RL_Sim::Forward()
torch::autograd::GradMode::set_enabled(false);
torch::Tensor clamped_obs = this->ComputeObservation();
torch::Tensor actions;
if(this->use_history)
if(this->params.use_history)
{
this->history_obs_buf.insert(clamped_obs);
this->history_obs = this->history_obs_buf.get_obs_vec({0, 1, 2, 3, 4, 5});