Skip to content

Commit

Permalink
feat: add humanoid gr1t1
Browse files Browse the repository at this point in the history
  • Loading branch information
fan-ziqi committed May 25, 2024
1 parent 9155e63 commit b1a944d
Show file tree
Hide file tree
Showing 47 changed files with 3,877 additions and 19 deletions.
45 changes: 36 additions & 9 deletions src/rl_sar/config.yaml
Original file line number Diff line number Diff line change
@@ -1,9 +1,4 @@
a1:
# order:
# FL
# FR
# RL
# RR
model_name: "model_0522.pt"
num_observations: 45
clip_obs: 100.0
Expand Down Expand Up @@ -48,7 +43,39 @@ a1:
-0.1000, 0.8000, -1.5000,
0.1000, 1.0000, -1.5000,
-0.1000, 1.0000, -1.5000]
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"]
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"
num_observations: 39
clip_obs: 100.0
clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691,
0.4391, 1.0491, 1.0491, 2.2691, 0.8691]
clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991,
-1.1391, -1.0491, -2.0991, -0.4391, -1.3991]
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: 0.5
hip_scale_reduction_indices: [0, 3, 6, 9]
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"]
52 changes: 52 additions & 0 deletions src/rl_sar/launch/gazebo_gr1t1.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
<launch>
<arg name="wname" default="stairs"/>
<arg name="rname" default="gr1t1"/>
<param name="robot_name" type="str" value="gr1t1"/>
<param name="use_history" type="bool" value="false"/>
<param name="ros_namespace" type="str" value="/$(arg rname)_gazebo/"/>
<arg name="robot_path" value="(find $(arg rname)_description)"/>
<arg name="dollar" value="$"/>

<arg name="paused" default="true"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>

<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find rl_sar)/worlds/$(arg wname).world"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>

<!-- Load the URDF into the ROS Parameter Server -->
<param name="robot_description" textfile="$(find gr1t1_description)/urdf/GR1T1_lower_limb.urdf"/>

<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<!-- Set trunk and joint positions at startup -->
<node pkg="gazebo_ros" type="spawn_model" name="urdf_spawner" respawn="false" output="screen"
args="-urdf -z 1.0 -model $(arg rname)_gazebo -param robot_description -unpause"/>

<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(arg dollar)$(arg robot_path)/config/robot_control.yaml" command="load"/>

<!-- <rosparam param="/gr1t1_gazebo/joint_state_controller/publish_rate">5000</rosparam> -->

<!-- load the controllers -->
<node pkg="controller_manager" type="spawner" name="controller_spawner" respawn="false"
output="screen" ns="/$(arg rname)_gazebo" args="joint_state_controller
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 "/>

<!-- convert joint states to TF transforms for rviz, etc -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/$(arg rname)_gazebo/joint_states"/>
</node>

<node pkg="rl_sar" type="rl_sim" name="rl_sim" output="screen"/>

</launch>
2 changes: 1 addition & 1 deletion src/rl_sar/library/rl_sdk/rl_sdk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ void RL::ReadYaml(std::string robot_name)
this->params.fixed_kd = torch::tensor(ReadVectorFromYaml<double>(config["fixed_kd"])).view({1, -1});
this->params.torque_limits = torch::tensor(ReadVectorFromYaml<double>(config["torque_limits"])).view({1, -1});
this->params.default_dof_pos = torch::tensor(ReadVectorFromYaml<double>(config["default_dof_pos"])).view({1, -1});
this->params.joint_names = ReadVectorFromYaml<std::string>(config["joint_names"]);
this->params.joint_controller_names = ReadVectorFromYaml<std::string>(config["joint_controller_names"]);
}

void RL::CSVInit(std::string robot_name)
Expand Down
2 changes: 1 addition & 1 deletion src/rl_sar/library/rl_sdk/rl_sdk.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ struct ModelParams
torch::Tensor fixed_kd;
torch::Tensor commands_scale;
torch::Tensor default_dof_pos;
std::vector<std::string> joint_names;
std::vector<std::string> joint_controller_names;
};

struct Observations
Expand Down
Binary file added src/rl_sar/models/gr1t1/model_4000_jit.pt
Binary file not shown.
16 changes: 8 additions & 8 deletions src/rl_sar/src/rl_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@ RL_Sim::RL_Sim()

// Due to the fact that the robot_state_publisher sorts the joint names alphabetically,
// the mapping table is established according to the order defined in the YAML file
std::vector<std::string> sorted_joint_names = params.joint_names;
std::sort(sorted_joint_names.begin(), sorted_joint_names.end());
for(size_t i = 0; i < params.joint_names.size(); ++i)
std::vector<std::string> sorted_joint_controller_names = params.joint_controller_names;
std::sort(sorted_joint_controller_names.begin(), sorted_joint_controller_names.end());
for(size_t i = 0; i < params.joint_controller_names.size(); ++i)
{
sorted_to_original_index[sorted_joint_names[i]] = i;
sorted_to_original_index[sorted_joint_controller_names[i]] = i;
}
mapped_joint_positions = std::vector<double>(params.num_of_dofs, 0.0);
mapped_joint_velocities = std::vector<double>(params.num_of_dofs, 0.0);
Expand All @@ -48,8 +48,8 @@ RL_Sim::RL_Sim()
for (int i = 0; i < params.num_of_dofs; ++i)
{
// joint need to rename as xxx_joint
torque_publishers[params.joint_names[i]] = nh.advertise<robot_msgs::MotorCommand>(
ros_namespace + params.joint_names[i].substr(0, params.joint_names[i].size() - 6) + "_controller/command", 10);
torque_publishers[params.joint_controller_names[i]] = nh.advertise<robot_msgs::MotorCommand>(
ros_namespace + params.joint_controller_names[i] + "/command", 10);
}

// subscriber
Expand Down Expand Up @@ -127,7 +127,7 @@ void RL_Sim::SetCommand(const RobotCommand<double> *command)

for(int i = 0; i < params.num_of_dofs; ++i)
{
torque_publishers[params.joint_names[i]].publish(motor_commands[i]);
torque_publishers[params.joint_controller_names[i]].publish(motor_commands[i]);
}
}

Expand Down Expand Up @@ -166,7 +166,7 @@ void RL_Sim::MapData(const std::vector<double>& source_data, std::vector<double>
{
for(size_t i = 0; i < source_data.size(); ++i)
{
target_data[i] = source_data[sorted_to_original_index[params.joint_names[i]]];
target_data[i] = source_data[sorted_to_original_index[params.joint_controller_names[i]]];
}
}

Expand Down
14 changes: 14 additions & 0 deletions src/robots/gr1t1_description/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 3.0)

project(gr1t1_description)

find_package(catkin REQUIRED)

catkin_package()

find_package(roslaunch)

foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)
57 changes: 57 additions & 0 deletions src/robots/gr1t1_description/config/robot_control.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
gr1t1_gazebo:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 1000

# left leg Controllers ---------------------------------------
l_hip_roll_controller:
type: robot_joint_controller/RobotJointController
joint: l_hip_roll
pid: {p: 57.0, i: 0.0, d: 5.7}

l_hip_yaw_controller:
type: robot_joint_controller/RobotJointController
joint: l_hip_yaw
pid: {p: 43.0, i: 0.0, d: 4.3}

l_hip_pitch_controller:
type: robot_joint_controller/RobotJointController
joint: l_hip_pitch
pid: {p: 114.0, i: 0.0, d: 11.4}

l_knee_pitch_controller:
type: robot_joint_controller/RobotJointController
joint: l_knee_pitch
pid: {p: 114.0, i: 0.0, d: 11.4}

l_ankle_pitch_controller:
type: robot_joint_controller/RobotJointController
joint: l_ankle_pitch
pid: {p: 15.3, i: 0.0, d: 1.5}

# right leg Controllers ---------------------------------------
r_hip_roll_controller:
type: robot_joint_controller/RobotJointController
joint: r_hip_roll
pid: {p: 57.0, i: 0.0, d: 5.7}

r_hip_yaw_controller:
type: robot_joint_controller/RobotJointController
joint: r_hip_yaw
pid: {p: 43.0, i: 0.0, d: 4.3}

r_hip_pitch_controller:
type: robot_joint_controller/RobotJointController
joint: r_hip_pitch
pid: {p: 114.0, i: 0.0, d: 11.4}

r_knee_pitch_controller:
type: robot_joint_controller/RobotJointController
joint: r_knee_pitch
pid: {p: 114.0, i: 0.0, d: 11.4}

r_ankle_pitch_controller:
type: robot_joint_controller/RobotJointController
joint: r_ankle_pitch
pid: {p: 15.3, i: 0.0, d: 1.5}
20 changes: 20 additions & 0 deletions src/robots/gr1t1_description/launch/display.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find gr1t1_description)/urdf/GR1T1_lower_limb.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find gr1t1_description)/urdf.rviz" />
</launch>
20 changes: 20 additions & 0 deletions src/robots/gr1t1_description/launch/gazebo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find gr1t1_description)/urdf/GR1T1_lower_limb.urdf -urdf -model gr1t1_description"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>
Binary file added src/robots/gr1t1_description/meshes/base.STL
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file added src/robots/gr1t1_description/meshes/head_yaw.STL
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Binary file added src/robots/gr1t1_description/meshes/waist_yaw.STL
Diff not rendered.
20 changes: 20 additions & 0 deletions src/robots/gr1t1_description/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<package format="2">
<name>gr1t1_description</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for gr1t1_description</p>
<p>This package contains configuration data, 3D models and launch files for fldlar_description robot</p>
</description>
<author>Ziqi Fan</author>
<maintainer email="[email protected]" />
<license>Apache</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
<export>
<architecture_independent />
</export>
</package>
Loading

0 comments on commit b1a944d

Please sign in to comment.