fix cyberdog model

This commit is contained in:
fan-ziqi 2024-04-05 20:28:43 +08:00
parent d709013bf4
commit f6fe3071d6
13 changed files with 142 additions and 1278 deletions

View File

@ -21,7 +21,7 @@ RL_Real::RL_Real() : CustomInterface(500)
this->params.clip_obs = 100.0;
this->params.clip_actions = 100.0;
this->params.damping = 0.5;
this->params.stiffness = 25;
this->params.stiffness = 20;
this->params.d_gains = torch::ones(12) * this->params.damping;
this->params.p_gains = torch::ones(12) * this->params.stiffness;
this->params.action_scale = 0.25;
@ -33,10 +33,10 @@ RL_Real::RL_Real() : CustomInterface(500)
this->params.dof_vel_scale = 0.05;
this->params.commands_scale = torch::tensor({this->params.lin_vel_scale, this->params.lin_vel_scale, this->params.ang_vel_scale});
this->params.torque_limits = torch::tensor({{17.0, 24.0, 24.0,
17.0, 24.0, 24.0,
17.0, 24.0, 24.0,
17.0, 24.0, 24.0}});
this->params.torque_limits = torch::tensor({{24.0, 24.0, 24.0,
24.0, 24.0, 24.0,
24.0, 24.0, 24.0,
24.0, 24.0, 24.0}});
// hip, thigh, calf
this->params.default_dof_pos = torch::tensor({{ 0.1000, 0.8000, -1.5000, // FL
@ -167,10 +167,10 @@ void RL_Real::RobotControl()
// cyberdogCmd.q_des[i] = 0;
cyberdogCmd.q_des[i] = output_dof_pos[0][dof_mapping[i]].item<double>();
cyberdogCmd.qd_des[i] = 0;
// cyberdogCmd.kp_des[i] = params.stiffness;
// cyberdogCmd.kd_des[i] = params.damping;
cyberdogCmd.kp_des[i] = Kp[dof_mapping[i]];
cyberdogCmd.kd_des[i] = Kd[dof_mapping[i]];
cyberdogCmd.kp_des[i] = params.stiffness;
cyberdogCmd.kd_des[i] = params.damping;
// cyberdogCmd.kp_des[i] = Kp[dof_mapping[i]];
// cyberdogCmd.kd_des[i] = Kd[dof_mapping[i]];
// cyberdogCmd.tau_des[i] = output_torques[0][dof_mapping[i]].item<double>();
cyberdogCmd.tau_des[i] = 0;
}

View File

@ -24,7 +24,7 @@ RL_Sim::RL_Sim()
this->params.clip_obs = 100.0;
this->params.clip_actions = 100.0;
this->params.damping = 0.5;
this->params.stiffness = 25;
this->params.stiffness = 20;
this->params.d_gains = torch::ones(12) * this->params.damping;
this->params.p_gains = torch::ones(12) * this->params.stiffness;
this->params.action_scale = 0.25;

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1,6 +1,6 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /Repository/我的文件/研究生/四足项目/RL/BlindDog/rl_sar/src/robots/cyberdog_description/xacro/robot.xacro | -->
<!-- | This document was autogenerated by xacro from rl_sar/src/robots/cyberdog1_description/xacro/robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="cyberdog_description">
@ -12,16 +12,16 @@
</plugin>
</gazebo>
<!-- Show the trajectory of trunk center. -->
<gazebo>
<plugin filename="libLinkPlot3DPlugin.so" name="3dplot">
<frequency>10</frequency>
<plot>
<link>base</link>
<pose>0 0 0 0 0 0</pose>
<material>Gazebo/Yellow</material>
</plot>
</plugin>
</gazebo>
<!-- <gazebo>
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
<frequency>10</frequency>
<plot>
<link>base</link>
<pose>0 0 0 0 0 0</pose>
<material>Gazebo/Yellow</material>
</plot>
</plugin>
</gazebo> -->
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
<!-- <gazebo>
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
@ -324,18 +324,19 @@
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<!-- <inertial>
<mass value="0.001" />
<origin rpy="0 0 0" xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<material name="red"/>
</visual>
<!-- <collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<box size=".001 .001 .001" />
@ -388,7 +389,7 @@
<inertia ixx="0.000403612" ixy="9.337e-06" ixz="5.36e-07" iyy="0.000600779" iyz="6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="FR_hip_rotor_fix" type="fixed">
<joint dont_collapse="true" name="FR_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="-0.0832504 0 0"/>
<parent link="FR_hip"/>
<child link="FR_hip_rotor"/>
@ -463,7 +464,7 @@
<inertia ixx="0.004811898" ixy="-9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="-0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="FR_thigh_rotor_fix" type="fixed">
<joint dont_collapse="true" name="FR_thigh_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.107226 0"/>
<parent link="FR_thigh"/>
<child link="FR_thigh_rotor"/>
@ -476,7 +477,7 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="FR_calf_rotor_fix" type="fixed">
<joint dont_collapse="true" name="FR_calf_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0426259 0"/>
<parent link="FR_thigh"/>
<child link="FR_calf_rotor"/>
@ -648,7 +649,7 @@
<inertia ixx="0.000403612" ixy="-9.337e-06" ixz="5.36e-07" iyy="0.000600779" iyz="-6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="FL_hip_rotor_fix" type="fixed">
<joint dont_collapse="true" name="FL_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="-0.0832504 0 0"/>
<parent link="FL_hip"/>
<child link="FL_hip_rotor"/>
@ -723,7 +724,7 @@
<inertia ixx="0.004811898" ixy="9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="FL_thigh_rotor_fix" type="fixed">
<joint dont_collapse="true" name="FL_thigh_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.107226 0"/>
<parent link="FL_thigh"/>
<child link="FL_thigh_rotor"/>
@ -736,7 +737,7 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="FL_calf_rotor_fix" type="fixed">
<joint dont_collapse="true" name="FL_calf_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0426259 0"/>
<parent link="FL_thigh"/>
<child link="FL_calf_rotor"/>
@ -908,7 +909,7 @@
<inertia ixx="0.000403612" ixy="-9.337e-06" ixz="-5.36e-07" iyy="0.000600779" iyz="6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="RR_hip_rotor_fix" type="fixed">
<joint dont_collapse="true" name="RR_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0.0832504 0 0"/>
<parent link="RR_hip"/>
<child link="RR_hip_rotor"/>
@ -983,7 +984,7 @@
<inertia ixx="0.004811898" ixy="-9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="-0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="RR_thigh_rotor_fix" type="fixed">
<joint dont_collapse="true" name="RR_thigh_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.107226 0"/>
<parent link="RR_thigh"/>
<child link="RR_thigh_rotor"/>
@ -996,7 +997,7 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="RR_calf_rotor_fix" type="fixed">
<joint dont_collapse="true" name="RR_calf_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0426259 0"/>
<parent link="RR_thigh"/>
<child link="RR_calf_rotor"/>
@ -1168,7 +1169,7 @@
<inertia ixx="0.000403612" ixy="9.337e-06" ixz="-5.36e-07" iyy="0.000600779" iyz="-6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="RL_hip_rotor_fix" type="fixed">
<joint dont_collapse="true" name="RL_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0.0832504 0 0"/>
<parent link="RL_hip"/>
<child link="RL_hip_rotor"/>
@ -1243,7 +1244,7 @@
<inertia ixx="0.004811898" ixy="9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="RL_thigh_rotor_fix" type="fixed">
<joint dont_collapse="true" name="RL_thigh_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.107226 0"/>
<parent link="RL_thigh"/>
<child link="RL_thigh_rotor"/>
@ -1256,7 +1257,7 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="RL_calf_rotor_fix" type="fixed">
<joint dont_collapse="true" name="RL_calf_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0426259 0"/>
<parent link="RL_thigh"/>
<child link="RL_calf_rotor"/>

View File

@ -67,6 +67,24 @@
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<material name="red"/>
</visual>
<!-- <collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision> -->
</link>
<joint name="FR_hip_joint" type="revolute">
@ -85,24 +103,23 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
<inertial>
<origin rpy="0 0 0" xyz="-0.001597914 -0.001680938 2.253e-06"/>
<mass value="0.537806728"/>
<inertia ixx="0.000403612" ixy="9.337e-06" ixz="5.36e-07" iyy="0.000600779" iyz="6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="FR_hip_rotor_fix" type="fixed">
<joint name="FR_hip_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="-0.0832504 0 0"/>
<parent link="FR_hip"/>
<child link="FR_hip_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="FR_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -123,12 +140,12 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.105076 0"/>
@ -158,12 +175,11 @@
<inertia ixx="0.004811898" ixy="-9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="-0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="FR_thigh_rotor_fix" type="fixed">
<joint name="FR_thigh_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 0.107226 0"/>
<parent link="FR_thigh"/>
<child link="FR_thigh_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="FR_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -171,12 +187,11 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="FR_calf_rotor_fix" type="fixed">
<joint name="FR_calf_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 0.0426259 0"/>
<parent link="FR_thigh"/>
<child link="FR_calf_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="FR_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -243,6 +258,10 @@
<sphere radius="0.018"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
<joint name="FL_hip_joint" type="revolute">
@ -261,24 +280,23 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
<inertial>
<origin rpy="0 0 0" xyz="-0.001597914 0.001680938 2.253e-06"/>
<mass value="0.537806728"/>
<inertia ixx="0.000403612" ixy="-9.337e-06" ixz="5.36e-07" iyy="0.000600779" iyz="-6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="FL_hip_rotor_fix" type="fixed">
<joint name="FL_hip_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="-0.0832504 0 0"/>
<parent link="FL_hip"/>
<child link="FL_hip_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="FL_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -299,12 +317,12 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
</link>
<joint name="FL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.105076 0"/>
@ -334,12 +352,11 @@
<inertia ixx="0.004811898" ixy="9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="FL_thigh_rotor_fix" type="fixed">
<joint name="FL_thigh_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 -0.107226 0"/>
<parent link="FL_thigh"/>
<child link="FL_thigh_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="FL_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -347,12 +364,11 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="FL_calf_rotor_fix" type="fixed">
<joint name="FL_calf_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 -0.0426259 0"/>
<parent link="FL_thigh"/>
<child link="FL_calf_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="FL_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -419,6 +435,10 @@
<sphere radius="0.018"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
<joint name="RR_hip_joint" type="revolute">
@ -437,24 +457,23 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
<inertial>
<origin rpy="0 0 0" xyz="0.001597914 -0.001680938 2.253e-06"/>
<mass value="0.537806728"/>
<inertia ixx="0.000403612" ixy="-9.337e-06" ixz="-5.36e-07" iyy="0.000600779" iyz="6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="RR_hip_rotor_fix" type="fixed">
<joint name="RR_hip_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0.0832504 0 0"/>
<parent link="RR_hip"/>
<child link="RR_hip_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="RR_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -475,12 +494,12 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
</link>
<joint name="RR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.105076 0"/>
@ -510,12 +529,11 @@
<inertia ixx="0.004811898" ixy="-9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="-0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="RR_thigh_rotor_fix" type="fixed">
<joint name="RR_thigh_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 0.107226 0"/>
<parent link="RR_thigh"/>
<child link="RR_thigh_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="RR_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -523,12 +541,11 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="RR_calf_rotor_fix" type="fixed">
<joint name="RR_calf_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 0.0426259 0"/>
<parent link="RR_thigh"/>
<child link="RR_calf_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="RR_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -595,8 +612,11 @@
<sphere radius="0.018"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
<!-- <xacro:leg_transmission name="${name}" /> -->
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.23035 0.05 0"/>
<parent link="trunk"/>
@ -613,24 +633,23 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
<inertial>
<origin rpy="0 0 0" xyz="0.001597914 0.001680938 2.253e-06"/>
<mass value="0.537806728"/>
<inertia ixx="0.000403612" ixy="9.337e-06" ixz="-5.36e-07" iyy="0.000600779" iyz="-6.3e-08" izz="0.000417249"/>
</inertial>
</link>
<joint name="RL_hip_rotor_fix" type="fixed">
<joint name="RL_hip_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0.0832504 0 0"/>
<parent link="RL_hip"/>
<child link="RL_hip_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="RL_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -651,12 +670,12 @@
</geometry>
<material name="silver"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.052" radius="0.047"/>
</geometry>
</collision>
</collision> -->
</link>
<joint name="RL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.105076 0"/>
@ -686,12 +705,11 @@
<inertia ixx="0.004811898" ixy="9.3647e-05" ixz="-0.000208709" iyy="0.004752366" iyz="0.000813258" izz="0.001079691"/>
</inertial>
</link>
<joint name="RL_thigh_rotor_fix" type="fixed">
<joint name="RL_thigh_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 -0.107226 0"/>
<parent link="RL_thigh"/>
<child link="RL_thigh_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="RL_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -699,12 +717,11 @@
<inertia ixx="4.5843e-05" ixy="0" ixz="0" iyy="4.5871e-05" iyz="0" izz="8.9031e-05"/>
</inertial>
</link>
<joint name="RL_calf_rotor_fix" type="fixed">
<joint name="RL_calf_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 -0.0426259 0"/>
<parent link="RL_thigh"/>
<child link="RL_calf_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="RL_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -771,5 +788,9 @@
<sphere radius="0.018"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.6e-06" ixy="0.0" ixz="0.0" iyy="9.6e-06" iyz="0.0" izz="9.6e-06"/>
</inertial>
</link>
</robot>

View File

@ -9,7 +9,7 @@
</gazebo>
<!-- Show the trajectory of trunk center. -->
<gazebo>
<!-- <gazebo>
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
<frequency>10</frequency>
<plot>
@ -18,7 +18,7 @@
<material>Gazebo/Yellow</material>
</plot>
</plugin>
</gazebo>
</gazebo> -->
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
<!-- <gazebo>

View File

@ -65,7 +65,7 @@
</inertial>
</link>
<joint name="${name}_hip_rotor_fix" type="fixed">
<joint name="${name}_hip_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="${-abad_rotor_offset*front_hind} 0 0" />
<parent link="${name}_hip" />
<child link="${name}_hip_rotor" />
@ -156,7 +156,7 @@
</inertial>
</link>
<joint name="${name}_thigh_rotor_fix" type="fixed">
<joint name="${name}_thigh_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 ${hip_rotor_offset*mirror} 0" />
<parent link="${name}_thigh" />
<child link="${name}_thigh_rotor" />
@ -171,7 +171,7 @@
</inertial>
</link>
<joint name="${name}_calf_rotor_fix" type="fixed">
<joint name="${name}_calf_rotor_fix" type="fixed" dont_collapse="true">
<origin rpy="0 0 0" xyz="0 ${knee_rotor_offset*mirror} 0" />
<parent link="${name}_thigh" />
<child link="${name}_calf_rotor" />

View File

@ -84,7 +84,7 @@
</joint>
<link name="imu_link">
<!-- <inertial>
<inertial>
<mass value="0.001" />
<origin rpy="0 0 0" xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
@ -94,8 +94,9 @@
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
<material name="red"/>
</visual>
<collision>
<!-- <collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<box size=".001 .001 .001" />

View File

@ -298,14 +298,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/trunk.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/trunk.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/trunk.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/trunk.STL"/>
</geometry>
</collision>
<inertial>
@ -353,14 +353,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip_mirror.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/hip_mirror.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip_mirror.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/hip_mirror.STL"/>
</geometry>
</collision>
<inertial>
@ -388,14 +388,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL"/>
</geometry>
</collision>
<inertial>
@ -416,14 +416,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL"/>
</geometry>
</collision>
<inertial>
@ -500,14 +500,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/hip.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/hip.STL"/>
</geometry>
</collision>
<inertial>
@ -535,14 +535,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL"/>
</geometry>
</collision>
<inertial>
@ -563,14 +563,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL"/>
</geometry>
</collision>
<inertial>
@ -647,14 +647,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip_mirror.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/hip_mirror.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip_mirror.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/hip_mirror.STL"/>
</geometry>
</collision>
<inertial>
@ -682,14 +682,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL"/>
</geometry>
</collision>
<inertial>
@ -710,14 +710,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL"/>
</geometry>
</collision>
<inertial>
@ -794,14 +794,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/hip.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/hip.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/hip.STL"/>
</geometry>
</collision>
<inertial>
@ -829,14 +829,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/thigh.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/thigh.STL"/>
</geometry>
</collision>
<inertial>
@ -857,14 +857,14 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL" scale="1 1 1"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://cyberdog_description/meshes/calf.STL"/>
<mesh filename="package://cyberdog_old_description/meshes/calf.STL"/>
</geometry>
</collision>
<inertial>