simplified structure for rl controller
This commit is contained in:
parent
f2062983fd
commit
ca3f76d09b
|
@ -112,6 +112,7 @@ namespace rl_quadruped_controller {
|
|||
RCLCPP_INFO(get_node()->get_logger(), "Controller Update Rate: %d Hz", ctrl_interfaces_.frequency_);
|
||||
|
||||
if (foot_force_interface_types_.size() == 4) {
|
||||
RCLCPP_INFO(get_node()->get_logger(), "Enable Estimator");
|
||||
ctrl_component_.enable_estimator_ = true;
|
||||
ctrl_component_.estimator_ = std::make_shared<Estimator>(ctrl_interfaces_, ctrl_component_);
|
||||
}
|
||||
|
|
|
@ -12,17 +12,17 @@ QuadrupedRobot::QuadrupedRobot(CtrlInterfaces &ctrl_interfaces, const std::strin
|
|||
KDL::Tree robot_tree;
|
||||
kdl_parser::treeFromString(robot_description, robot_tree);
|
||||
|
||||
robot_tree.getChain(base_name, feet_names[0], fr_chain_);
|
||||
robot_tree.getChain(base_name, feet_names[1], fl_chain_);
|
||||
robot_tree.getChain(base_name, feet_names[2], rr_chain_);
|
||||
robot_tree.getChain(base_name, feet_names[3], rl_chain_);
|
||||
robot_tree.getChain(base_name, feet_names[0], fl_chain_);
|
||||
robot_tree.getChain(base_name, feet_names[1], fr_chain_);
|
||||
robot_tree.getChain(base_name, feet_names[2], rl_chain_);
|
||||
robot_tree.getChain(base_name, feet_names[3], rr_chain_);
|
||||
|
||||
|
||||
robot_legs_.resize(4);
|
||||
robot_legs_[0] = std::make_shared<RobotLeg>(fr_chain_);
|
||||
robot_legs_[1] = std::make_shared<RobotLeg>(fl_chain_);
|
||||
robot_legs_[2] = std::make_shared<RobotLeg>(rr_chain_);
|
||||
robot_legs_[3] = std::make_shared<RobotLeg>(rl_chain_);
|
||||
robot_legs_[0] = std::make_shared<RobotLeg>(fl_chain_);
|
||||
robot_legs_[1] = std::make_shared<RobotLeg>(fr_chain_);
|
||||
robot_legs_[2] = std::make_shared<RobotLeg>(rl_chain_);
|
||||
robot_legs_[3] = std::make_shared<RobotLeg>(rr_chain_);
|
||||
|
||||
current_joint_pos_.resize(4);
|
||||
current_joint_vel_.resize(4);
|
||||
|
|
|
@ -187,8 +187,8 @@ rl_quadruped_controller:
|
|||
foot_force_name: "foot_force"
|
||||
foot_force_interfaces:
|
||||
- FL
|
||||
- RL
|
||||
- FR
|
||||
- RL
|
||||
- RR
|
||||
|
||||
imu_name: "imu_sensor"
|
||||
|
|
|
@ -0,0 +1,41 @@
|
|||
model_name: "himloco.pt"
|
||||
framework: "isaacgym"
|
||||
rows: 4
|
||||
cols: 3
|
||||
decimation: 4
|
||||
num_observations: 45
|
||||
observations: ["commands", "ang_vel", "gravity_vec", "dof_pos", "dof_vel", "actions"]
|
||||
observations_history: [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: [40, 40, 40,
|
||||
40, 40, 40,
|
||||
40, 40, 40,
|
||||
40, 40, 40]
|
||||
rl_kd: [1, 1, 1,
|
||||
1, 1, 1,
|
||||
1, 1, 1,
|
||||
1, 1, 1]
|
||||
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]
|
Loading…
Reference in New Issue