feat: add humanoid gr1t1

This commit is contained in:
fan-ziqi 2024-05-25 17:32:39 +08:00
parent 9155e6383b
commit b1a944dfc3
47 changed files with 3877 additions and 19 deletions

View File

@ -1,9 +1,4 @@
a1:
# order:
# FL
# FR
# RL
# RR
model_name: "model_0522.pt"
num_observations: 45
clip_obs: 100.0
@ -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"]

View File

@ -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>

View File

@ -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)

View File

@ -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

Binary file not shown.

View File

@ -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);
@ -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
@ -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]);
}
}
@ -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]]];
}
}

View File

@ -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)

View File

@ -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}

View File

@ -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>

View File

@ -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 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.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -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="fanziqi614@gmail.com" />
<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>

View File

@ -0,0 +1,225 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 549
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
10:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
11:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
12:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
13:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
20:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
21:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
22:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
23:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
30:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
31:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
32:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
33:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
40:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
41:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
42:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
43:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: base
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 2.634476661682129
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0.0988716408610344
Y: 0.08353396505117416
Z: -0.19447802007198334
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.5753985047340393
Target Frame: <Fixed Frame>
Yaw: 0.47539806365966797
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000003bc00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 278
Y: 96

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff