mirror of https://github.com/fan-ziqi/rl_sar.git
fix: change ReadVectorFromYaml && add commands_scale
This commit is contained in:
parent
70a5492b63
commit
d53d2078a8
|
@ -20,6 +20,7 @@ a1:
|
||||||
ang_vel_scale: 0.25
|
ang_vel_scale: 0.25
|
||||||
dof_pos_scale: 1.0
|
dof_pos_scale: 1.0
|
||||||
dof_vel_scale: 0.05
|
dof_vel_scale: 0.05
|
||||||
|
commands_scale: [1.0, 1.0, 1.0]
|
||||||
torque_limits: [33.5, 33.5, 33.5, # FL
|
torque_limits: [33.5, 33.5, 33.5, # FL
|
||||||
33.5, 33.5, 33.5, # FR
|
33.5, 33.5, 33.5, # FR
|
||||||
33.5, 33.5, 33.5, # RL
|
33.5, 33.5, 33.5, # RL
|
||||||
|
@ -55,6 +56,7 @@ cyberdog1:
|
||||||
ang_vel_scale: 0.25
|
ang_vel_scale: 0.25
|
||||||
dof_pos_scale: 1.0
|
dof_pos_scale: 1.0
|
||||||
dof_vel_scale: 0.05
|
dof_vel_scale: 0.05
|
||||||
|
commands_scale: [1.0, 1.0, 1.0]
|
||||||
torque_limits: [24.0, 24.0, 24.0, # FL
|
torque_limits: [24.0, 24.0, 24.0, # FL
|
||||||
24.0, 24.0, 24.0, # FR
|
24.0, 24.0, 24.0, # FR
|
||||||
24.0, 24.0, 24.0, # RL
|
24.0, 24.0, 24.0, # RL
|
||||||
|
@ -67,3 +69,74 @@ cyberdog1:
|
||||||
"FR_hip_joint", "FR_thigh_joint", "FR_calf_joint",
|
"FR_hip_joint", "FR_thigh_joint", "FR_calf_joint",
|
||||||
"RL_hip_joint", "RL_thigh_joint", "RL_calf_joint",
|
"RL_hip_joint", "RL_thigh_joint", "RL_calf_joint",
|
||||||
"RR_hip_joint", "RR_thigh_joint", "RR_calf_joint"]
|
"RR_hip_joint", "RR_thigh_joint", "RR_calf_joint"]
|
||||||
|
|
||||||
|
lite3_wheel:
|
||||||
|
num_observations: 45
|
||||||
|
clip_obs: 100.0
|
||||||
|
clip_actions: 100.0
|
||||||
|
# damping: 0.5
|
||||||
|
# stiffness: 20.0
|
||||||
|
p_gains: [20, 20, 20, 0, # FL
|
||||||
|
20, 20, 20, 0, # FR
|
||||||
|
20, 20, 20, 0, # RL
|
||||||
|
20, 20, 20, 0] # RR
|
||||||
|
d_gains: [0.5, 0.5, 0.5, 0.5, # FL
|
||||||
|
0.5, 0.5, 0.5, 0.5, # FR
|
||||||
|
0.5, 0.5, 0.5, 0.5, # RL
|
||||||
|
0.5, 0.5, 0.5, 0.5] # RR
|
||||||
|
action_scale: 0.25
|
||||||
|
hip_scale_reduction: 1.0
|
||||||
|
num_of_dofs: 16
|
||||||
|
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: [21.6, 21.6, 32.4, 1.8, # FL
|
||||||
|
21.6, 21.6, 32.4, 1.8, # FR
|
||||||
|
21.6, 21.6, 32.4, 1.8, # RL
|
||||||
|
21.6, 21.6, 32.4, 1.8] # RR
|
||||||
|
default_dof_pos: [ 0.1000, 0.8000, -1.5000, 0.0000, # FL
|
||||||
|
-0.1000, 0.8000, -1.5000, 0.0000, # FR
|
||||||
|
0.1000, 1.0000, -1.5000, 0.0000, # RL
|
||||||
|
-0.1000, 1.0000, -1.5000, 0.0000] # RR
|
||||||
|
joint_names: ["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"]
|
||||||
|
|
||||||
|
fldlar:
|
||||||
|
model_name: "model_0514.pt"
|
||||||
|
num_observations: 45
|
||||||
|
clip_obs: 100.0
|
||||||
|
clip_actions: 100.0
|
||||||
|
# damping: 0.5
|
||||||
|
# stiffness: 20.0
|
||||||
|
p_gains: [200, 200, 200, # FL
|
||||||
|
200, 200, 200, # FR
|
||||||
|
200, 200, 200, # RL
|
||||||
|
200, 200, 200] # RR
|
||||||
|
d_gains: [11, 11, 11, # FL
|
||||||
|
11, 11, 11, # FR
|
||||||
|
11, 11, 11, # RL
|
||||||
|
11, 11, 11] # RR
|
||||||
|
action_scale: 0.25
|
||||||
|
hip_scale_reduction: 0.5
|
||||||
|
num_of_dofs: 12
|
||||||
|
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: [151.0, 151.0, 151.0, # FL
|
||||||
|
151.0, 151.0, 151.0, # FR
|
||||||
|
151.0, 151.0, 151.0, # RL
|
||||||
|
151.0, 151.0, 151.0] # RR
|
||||||
|
default_dof_pos: [0.0, 0.0, 0.0, # FL
|
||||||
|
0.0, 0.0, 0.0, # FR
|
||||||
|
0.0, 0.0, 0.0, # RL
|
||||||
|
0.0, 0.0, 0.0] # RR
|
||||||
|
joint_names: ["ip1x_hip_roll_joint", "ip1x_hip_pitch_joint", "ip1x_knee_joint",
|
||||||
|
"ip3x_hip_roll_joint", "ip3x_hip_pitch_joint", "ip3x_knee_joint",
|
||||||
|
"ip5x_hip_roll_joint", "ip5x_hip_pitch_joint", "ip5x_knee_joint",
|
||||||
|
"ip7x_hip_roll_joint", "ip7x_hip_pitch_joint", "ip7x_knee_joint"]
|
||||||
|
|
|
@ -1,13 +1,14 @@
|
||||||
#include "rl_sdk.hpp"
|
#include "rl_sdk.hpp"
|
||||||
|
|
||||||
torch::Tensor ReadTensorFromYaml(const YAML::Node& node)
|
template<typename T>
|
||||||
|
std::vector<T> ReadVectorFromYaml(const YAML::Node& node)
|
||||||
{
|
{
|
||||||
std::vector<float> values;
|
std::vector<T> values;
|
||||||
for(const auto& val : node)
|
for(const auto& val : node)
|
||||||
{
|
{
|
||||||
values.push_back(val.as<float>());
|
values.push_back(val.as<T>());
|
||||||
}
|
}
|
||||||
return torch::tensor(values).view({1, -1});
|
return values;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RL::ReadYaml(std::string robot_name)
|
void RL::ReadYaml(std::string robot_name)
|
||||||
|
@ -33,21 +34,17 @@ void RL::ReadYaml(std::string robot_name)
|
||||||
this->params.lin_vel_scale = config["lin_vel_scale"].as<float>();
|
this->params.lin_vel_scale = config["lin_vel_scale"].as<float>();
|
||||||
this->params.ang_vel_scale = config["ang_vel_scale"].as<float>();
|
this->params.ang_vel_scale = config["ang_vel_scale"].as<float>();
|
||||||
this->params.dof_pos_scale = config["dof_pos_scale"].as<float>();
|
this->params.dof_pos_scale = config["dof_pos_scale"].as<float>();
|
||||||
this->params.dof_vel_scale =config["dof_vel_scale"].as<float>();
|
this->params.dof_vel_scale = config["dof_vel_scale"].as<float>();
|
||||||
this->params.commands_scale = torch::tensor({this->params.lin_vel_scale, this->params.lin_vel_scale, this->params.ang_vel_scale * 2});
|
this->params.commands_scale = torch::tensor(ReadVectorFromYaml<float>(config["commands_scale"])).view({1, -1})
|
||||||
// this->params.damping = config["damping"].as<float>();
|
// this->params.damping = config["damping"].as<float>();
|
||||||
// this->params.stiffness = config["stiffness"].as<float>();
|
// this->params.stiffness = config["stiffness"].as<float>();
|
||||||
// this->params.d_gains = torch::ones(12) * this->params.damping;
|
// this->params.d_gains = torch::ones(12) * this->params.damping;
|
||||||
// this->params.p_gains = torch::ones(12) * this->params.stiffness;
|
// this->params.p_gains = torch::ones(12) * this->params.stiffness;
|
||||||
this->params.p_gains = ReadTensorFromYaml(config["p_gains"]);
|
this->params.p_gains = torch::tensor(ReadVectorFromYaml<float>(config["p_gains"])).view({1, -1})
|
||||||
this->params.d_gains = ReadTensorFromYaml(config["d_gains"]);
|
this->params.d_gains = torch::tensor(ReadVectorFromYaml<float>(config["d_gains"])).view({1, -1});
|
||||||
this->params.torque_limits = ReadTensorFromYaml(config["torque_limits"]);
|
this->params.torque_limits = torch::tensor(ReadVectorFromYaml<float>(config["torque_limits"])).view({1, -1});
|
||||||
this->params.default_dof_pos = ReadTensorFromYaml(config["default_dof_pos"]);
|
this->params.default_dof_pos = torch::tensor(ReadVectorFromYaml<float>(config["default_dof_pos"])).view({1, -1});
|
||||||
const YAML::Node& joint_names_node = config["joint_names"];
|
this->params.joint_names = ReadVectorFromYaml<std::string>(config["joint_names"]);
|
||||||
for(const auto& name : joint_names_node)
|
|
||||||
{
|
|
||||||
this->params.joint_names.push_back(name.as<std::string>());
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void RL::CSVInit(std::string robot_name)
|
void RL::CSVInit(std::string robot_name)
|
||||||
|
|
Loading…
Reference in New Issue