The generated urdf links do not contain visual and collision elements
Closed this issue ยท 10 comments
I tried to generate the urdf
model contained in the test/
folder of this repository. The yaml
configuration files contains details concerning the meshes renaming in the urdf
, see https://github.com/robotology/simmechanics-to-urdf/blob/master/test/legs_simmechanics_options.yaml#L1.
However, the generated urdf links do not contain any visual and collision elements. See the generated urdf below:
<robot name="iCubHeidelberg01_SIM_MODEL">
<link name="root_link">
<inertial>
<origin xyz="0.0251137 0.000104218 -0.0437451" rpy="1.57079632679 0 -1.57079632679"/>
<mass value="5.1504"/>
<inertia ixx="0.0140911" ixy="6.63933e-05" ixz="-8.71849e-05" iyy="0.0205529" iyz="-0.00172034" izz="0.0252712"/>
</inertial>
</link>
<link name="r_hip_1">
<inertial>
<origin xyz="-0.0529681 -4e-05 -0.0005388" rpy="0 0 0"/>
<mass value="0.9279"/>
<inertia ixx="0.000403391" ixy="-1.44877e-06" ixz="2.87683e-06" iyy="0.000572457" iyz="-1.70772e-07" izz="0.00057759"/>
</inertial>
</link>
<joint name="r_hip_pitch" type="revolute">
<origin xyz="0.0064515 0.0111 -0.119913" rpy="1.57079632679 0 -1.57079632679"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="root_link"/>
<child link="r_hip_1"/>
<limit effort="50000" lower="-0.523598775598" upper="1.4835298642" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="r_hip_2">
<inertial>
<origin xyz="3.49999999999e-06 -0.044278 0.0249831" rpy="0 0 0"/>
<mass value="0.4184"/>
<inertia ixx="0.000487899" ixy="-2.35279e-07" ixz="1.93211e-07" iyy="0.000286147" iyz="1.23695e-05" izz="0.000315134"/>
</inertial>
</link>
<joint name="r_hip_roll" type="revolute">
<origin xyz="-0.059 0 -0.0263622" rpy="0 0 0"/>
<axis xyz="0.0 0.0 1.0"/>
<parent link="r_hip_1"/>
<child link="r_hip_2"/>
<limit effort="50000" lower="0.0" upper="1.57079632679" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="r_hip_3">
<inertial>
<origin xyz="-0.000123 -0.0002823 0.008718" rpy="-1.57079632679 0 -1.57079632679"/>
<mass value="0.1262"/>
<inertia ixx="3.34665e-05" ixy="7.47286e-08" ixz="-4.04554e-08" iyy="5.70757e-05" iyz="-8.80407e-08" izz="3.33523e-05"/>
</inertial>
</link>
<joint name="r_leg_ft_sensor" type="fixed">
<origin xyz="0 -0.0743 0.0255047" rpy="1.57079632679 -1.57079632679 0"/>
<parent link="r_hip_2"/>
<child link="r_hip_3"/>
<dynamics damping="0.1"/>
</joint>
<link name="r_upper_leg">
<inertial>
<origin xyz="-5.89e-05 -0.079146 0.0033012" rpy="0 0 0"/>
<mass value="2.2544"/>
<inertia ixx="0.00794621" ixy="0.000169783" ixz="9.58795e-06" iyy="0.00179234" iyz="-0.000163445" izz="0.00796958"/>
</inertial>
</link>
<joint name="r_hip_yaw" type="revolute">
<origin xyz="0 0 0.018" rpy="-1.57079632679 0 -1.57079632679"/>
<axis xyz="0.0 -1.0 0.0"/>
<parent link="r_hip_3"/>
<child link="r_upper_leg"/>
<limit effort="50000" lower="-1.2217304764" upper="1.2217304764" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="r_lower_leg">
<inertial>
<origin xyz="0.0117639 -0.083358 0.0024521" rpy="0 0 0"/>
<mass value="1.7086"/>
<inertia ixx="0.00565145" ixy="0.000651976" ixz="1.347e-05" iyy="0.00170964" iyz="-0.000147573" izz="0.00615412"/>
</inertial>
</link>
<joint name="r_knee" type="revolute">
<origin xyz="-0.017957 -0.145625 0" rpy="0 0 0"/>
<axis xyz="-1.0 0.0 0.0"/>
<parent link="r_upper_leg"/>
<child link="r_lower_leg"/>
<limit effort="50000" lower="-1.74532925199" upper="0.0" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="r_ankle_1">
<inertial>
<origin xyz="0.034639 -4.73650698208e-05 0.0151613988639" rpy="0 0 0"/>
<mass value="0.8929"/>
<inertia ixx="0.000539928" ixy="-6.33371e-07" ixz="-3.92688e-05" iyy="0.00058171" iyz="1.26546e-06" izz="0.000414634"/>
</inertial>
</link>
<joint name="r_ankle_pitch" type="revolute">
<origin xyz="-0.021343 -0.201 0" rpy="-2.40788999988e-05 0 0"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="r_lower_leg"/>
<child link="r_ankle_1"/>
<limit effort="50000" lower="-0.349065850399" upper="0.523598775598" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="r_ankle_2">
<inertial>
<origin xyz="-8.19999999999e-06 -0.0382019454736 -0.0437950868735" rpy="0 0 0"/>
<mass value="0.2675"/>
<inertia ixx="0.000329604" ixy="6.02821e-07" ixz="7.59365e-08" iyy="0.000253765" iyz="-1.08449e-08" izz="0.000148708"/>
</inertial>
</link>
<joint name="r_ankle_roll" type="revolute">
<origin xyz="0.0355 0 0.0445624670112" rpy="0 0 0"/>
<axis xyz="0.0 3.49019587103e-15 -1.00000000029"/>
<parent link="r_ankle_1"/>
<child link="r_ankle_2"/>
<limit effort="50000" lower="-0.349065850399" upper="0.349065850399" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="r_foot">
<inertial>
<origin xyz="0.033882827801 0.0054048 -0.00115418414893" rpy="-1.57079632708 0 -1.57079632679"/>
<mass value="3"/>
<inertia ixx="0.0003" ixy="-7.03830521877e-06" ixz="-0.000461427517132" iyy="0.0003" iyz="-6.20681338956e-05" izz="0.0003"/>
</inertial>
</link>
<joint name="r_foot_ft_sensor" type="fixed">
<origin xyz="0 -0.0603008427249 -0.0480625189919" rpy="3.14159265359 -1.57079632651 -1.57079632679"/>
<parent link="r_ankle_2"/>
<child link="r_foot"/>
<dynamics damping="0.1"/>
</joint>
<link name="r_sole"/>
<joint name="r_sole_fixed_joint" type="fixed">
<origin xyz="0 0 0.0144000000055" rpy="-3.14159265359 0 0"/>
<parent link="r_foot"/>
<child link="r_sole"/>
<dynamics damping="0.1"/>
</joint>
<link name="l_hip_1">
<inertial>
<origin xyz="-0.0529681 -3.63786457601e-05 0.000539056614961" rpy="-3.14159265359 -1.5640768048 1.57079632679"/>
<mass value="0.9279"/>
<inertia ixx="0.00057759" ixy="-2.87683e-06" ixz="1.70772e-07" iyy="0.000403391" iyz="-1.44877e-06" izz="0.000572457"/>
</inertial>
</link>
<joint name="l_hip_pitch" type="revolute">
<origin xyz="0.0064515 -0.0111 -0.119913" rpy="1.57751584879 0 1.57079632679"/>
<axis xyz="-1.0 0.0 0.0"/>
<parent link="root_link"/>
<child link="l_hip_1"/>
<limit effort="50000" lower="-0.523598775598" upper="1.4835298642" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="l_hip_2">
<inertial>
<origin xyz="3.50000000004e-06 -0.0442668735976 -0.0246856073077" rpy="-3.14159265359 -1.5640768048 1.57079632679"/>
<mass value="0.4184"/>
<inertia ixx="0.000315134" ixy="-1.93211e-07" ixz="-1.23695e-05" iyy="0.000487899" iyz="-2.35279e-07" izz="0.000286147"/>
</inertial>
</link>
<joint name="l_hip_roll" type="revolute">
<origin xyz="-0.059 -8.59963575406e-07 0.026362200929" rpy="0 0 0"/>
<axis xyz="0.0 -1.42487008564e-09 0.999999575903"/>
<parent link="l_hip_1"/>
<child link="l_hip_2"/>
<limit effort="50000" lower="0.0" upper="1.57079632679" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="l_hip_3">
<inertial>
<origin xyz="-0.0006222 0.0002823 0.008713" rpy="-3.14159265359 0 -3.14159265359"/>
<mass value="0.1262"/>
<inertia ixx="3.33523e-05" ixy="4.04554e-08" ixz="8.80407e-08" iyy="3.34665e-05" iyz="7.47286e-08" izz="5.70757e-05"/>
</inertial>
</link>
<joint name="l_leg_ft_sensor" type="fixed">
<origin xyz="0 -0.0743000549473 -0.0255046186937" rpy="0 1.5640768048 -1.57079632679"/>
<parent link="l_hip_2"/>
<child link="l_hip_3"/>
<dynamics damping="0.1"/>
</joint>
<link name="l_upper_leg">
<inertial>
<origin xyz="-5.88999999999e-05 -0.0791582282008 -0.0021491470665" rpy="-3.14159265359 -1.5640768048 1.57079632679"/>
<mass value="2.2544"/>
<inertia ixx="0.00796958" ixy="-9.58795e-06" ixz="0.000163445" iyy="0.00794621" iyz="0.000169783" izz="0.00179234"/>
</inertial>
</link>
<joint name="l_hip_yaw" type="revolute">
<origin xyz="0.000121 0 0.017999" rpy="-1.5640768048 0 1.57079632679"/>
<axis xyz="0.0 0.999999575903 1.4248700891e-09"/>
<parent link="l_hip_3"/>
<child link="l_upper_leg"/>
<limit effort="50000" lower="-1.2217304764" upper="1.2217304764" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="l_lower_leg">
<inertial>
<origin xyz="0.0117639 -0.0833608525374 -0.000293265754161" rpy="-3.14159265359 -1.5640768048 1.57079632679"/>
<mass value="1.7086"/>
<inertia ixx="0.00615412" ixy="-1.347e-05" ixz="0.000147573" iyy="0.00565145" iyz="0.000651976" izz="0.00170964"/>
</inertial>
</link>
<joint name="l_knee" type="revolute">
<origin xyz="-0.017957 -0.145625287455 0" rpy="0 0 0"/>
<axis xyz="-1.0 0.0 0.0"/>
<parent link="l_upper_leg"/>
<child link="l_lower_leg"/>
<limit effort="50000" lower="-1.74532925199" upper="0.0" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="l_ankle_1">
<inertial>
<origin xyz="0.034639 -0.000149240603678 -0.0151607383132" rpy="3.14159265359 -1.5640527248 1.57079632679"/>
<mass value="0.8929"/>
<inertia ixx="0.000414633939155" ixy="3.92687847377e-05" ixz="-1.26143699224e-06" iyy="0.000539928" iyz="-6.34316549325e-07" izz="0.000581710060845"/>
</inertial>
</link>
<joint name="l_ankle_pitch" type="revolute">
<origin xyz="-0.021343 -0.200983719847 0.00294927094483" rpy="2.40800041309e-05 0 0"/>
<axis xyz="-1.0 0.0 0.0"/>
<parent link="l_lower_leg"/>
<child link="l_ankle_1"/>
<limit effort="50000" lower="-0.349065850399" upper="0.523598775598" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="l_ankle_2">
<inertial>
<origin xyz="-8.19999999983e-06 -0.0381899139561 0.0470011143392" rpy="3.14159265359 -1.5640527248 1.57079632679"/>
<mass value="0.2675"/>
<inertia ixx="0.000148708000583" ixy="-7.59219847113e-08" ixz="1.33745569836e-08" iyy="0.000329604" iyz="6.02822828293e-07" izz="0.000253764999417"/>
</inertial>
</link>
<joint name="l_ankle_roll" type="revolute">
<origin xyz="0.0355 -1.6398477099e-05 -0.0475117797388" rpy="0 0 0"/>
<axis xyz="0.0 -8.83422736873e-10 0.999999737998"/>
<parent link="l_ankle_1"/>
<child link="l_ankle_2"/>
<limit effort="50000" lower="-0.349065850399" upper="0.349065850399" velocity="50000"/>
<dynamics damping="0.223"/>
</joint>
<link name="l_foot">
<inertial>
<origin xyz="0.0305282 -0.0054048 -0.001173" rpy="-3.14159265359 0 -3.14159265359"/>
<mass value="0.3794"/>
<inertia ixx="0.000283689378669" ixy="5.83551785502e-05" ixz="7.87664576035e-06" iyy="0.00121493" iyz="-8.91516128767e-07" izz="0.00140897962133"/>
</inertial>
</link>
<joint name="l_foot_ft_sensor" type="fixed">
<origin xyz="0 -0.0603002589183 0.0480625407102" rpy="0 1.5640527248 -1.57079632679"/>
<parent link="l_ankle_2"/>
<child link="l_foot"/>
<dynamics damping="0.1"/>
</joint>
<link name="l_sole"/>
<joint name="l_sole_fixed_joint" type="fixed">
<origin xyz="9.72e-05 0 0.014399" rpy="-3.14159265359 0.00674386312028 0"/>
<parent link="l_foot"/>
<child link="l_sole"/>
<dynamics damping="0.1"/>
</joint>
<link name="torso_1">
<inertial>
<origin xyz="0.0393679204 0.0293082 0.000142300004739" rpy="0 0 0"/>
<mass value="0.7112"/>
<inertia ixx="0.000416742" ixy="-8.88072e-07" ixz="1.08936e-07" iyy="0.000392401" iyz="5.37987e-06" izz="0.000307697"/>
</inertial>
</link>
<joint name="torso_pitch" type="revolute">
<origin xyz="0 0.0394 0" rpy="1.57079632663 0 -1.57079632679"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="root_link"/>
<child link="torso_1"/>
<limit effort="50000" lower="-0.349065850399" upper="1.2217304764" velocity="50000"/>
<dynamics damping="0.06"/>
</joint>
<link name="torso_2">
<inertial>
<origin xyz="-0.000121587809265 0.0287460000001 0.0580375000046" rpy="0 0 0"/>
<mass value="0.3954"/>
<inertia ixx="0.000620392" ixy="3.75632e-07" ixz="1.15418e-07" iyy="0.000446223" iyz="2.06978e-05" izz="0.00039084"/>
</inertial>
</link>
<joint name="torso_roll" type="revolute">
<origin xyz="0.0393999998093 0.032 -0.0587918999948" rpy="0 0 0"/>
<axis xyz="0.0 5.16987882846e-26 -1.0"/>
<parent link="torso_1"/>
<child link="torso_2"/>
<limit effort="50000" lower="-0.523598775598" upper="0.523598775598" velocity="50000"/>
<dynamics damping="0.06"/>
</joint>
<link name="chest">
<inertial>
<origin xyz="-0.000279596809265 0.0998630000009 -0.00564929998385" rpy="0 0 0"/>
<mass value="6.1306"/>
<inertia ixx="0.0252769" ixy="1.73516e-05" ixz="-0.0001136" iyy="0.0497471" iyz="0.000340001" izz="0.0580977"/>
</inertial>
</link>
<joint name="torso_yaw" type="revolute">
<origin xyz="0 0.0514999999991 0.0642919000083" rpy="0 0 0"/>
<axis xyz="0.0 -1.0 -5.16987882846e-26"/>
<parent link="torso_2"/>
<child link="chest"/>
<limit effort="50000" lower="-0.872664625997" upper="0.872664625997" velocity="50000"/>
<dynamics damping="0.06"/>
</joint>
<link name="imu_frame"/>
<joint name="imu_frame_fixed_joint" type="fixed">
<origin xyz="-0.0169999998093 0.100500000006 -0.0380999999838" rpy="-3.14159265359 0 0"/>
<parent link="chest"/>
<child link="imu_frame"/>
<dynamics damping="0.1"/>
</joint>
<link name="WEIGHT-1KG-4">
<inertial>
<origin xyz="-1e-06 1.46e-05 -1e-06" rpy="0 0 0"/>
<mass value="1.00161"/>
<inertia ixx="0.0010891" ixy="3.14425e-08" ixz="0.0" iyy="0.00108866" iyz="4.73842e-08" izz="0.00213553"/>
</inertial>
</link>
<joint name="chest_weight_5" type="fixed">
<origin xyz="-0.132249999809 0.0955 0" rpy="1.57079632679 0 1.57079632679"/>
<parent link="chest"/>
<child link="WEIGHT-1KG-4"/>
<dynamics damping="0.1"/>
</joint>
<link name="WEIGHT-1KG-3">
<inertial>
<origin xyz="-1.137569265e-06 1.46000000002e-05 -9.99999997586e-07" rpy="0 0 0"/>
<mass value="1.00161"/>
<inertia ixx="0.0010891" ixy="3.14425e-08" ixz="0.0" iyy="0.00108866" iyz="4.73842e-08" izz="0.00213553"/>
</inertial>
</link>
<joint name="chest_weight_4" type="fixed">
<origin xyz="0 0.22525 0" rpy="1.57079632679 0 0"/>
<parent link="chest"/>
<child link="WEIGHT-1KG-3"/>
<dynamics damping="0.1"/>
</joint>
<link name="WEIGHT-1KG-5">
<inertial>
<origin xyz="-1e-06 1.46e-05 -1e-06" rpy="0 0 0"/>
<mass value="1.00161"/>
<inertia ixx="0.0010891" ixy="3.14425e-08" ixz="0.0" iyy="0.00108866" iyz="4.73842e-08" izz="0.00213553"/>
</inertial>
</link>
<joint name="chest_weight_6" type="fixed">
<origin xyz="-0.150749999809 0.0955 0" rpy="1.57079632679 0 1.57079632679"/>
<parent link="chest"/>
<child link="WEIGHT-1KG-5"/>
<dynamics damping="0.1"/>
</joint>
<link name="WEIGHT-1KG">
<inertial>
<origin xyz="-1.00000000003e-06 1.46e-05 -1e-06" rpy="0 0 0"/>
<mass value="1.00161"/>
<inertia ixx="0.0010891" ixy="3.14425e-08" ixz="0.0" iyy="0.00108866" iyz="4.73842e-08" izz="0.00213553"/>
</inertial>
</link>
<joint name="chest_weight_1" type="fixed">
<origin xyz="0.132250000191 0.0955 0" rpy="1.57079632679 0 -1.57079632679"/>
<parent link="chest"/>
<child link="WEIGHT-1KG"/>
<dynamics damping="0.1"/>
</joint>
<link name="WEIGHT-1KG-2">
<inertial>
<origin xyz="-1.137569265e-06 1.46000000002e-05 -9.99999997642e-07" rpy="0 0 0"/>
<mass value="1.00161"/>
<inertia ixx="0.0010891" ixy="3.14425e-08" ixz="0.0" iyy="0.00108866" iyz="4.73842e-08" izz="0.00213553"/>
</inertial>
</link>
<joint name="chest_weight_3" type="fixed">
<origin xyz="0 0.20675 0" rpy="1.57079632679 0 0"/>
<parent link="chest"/>
<child link="WEIGHT-1KG-2"/>
<dynamics damping="0.1"/>
</joint>
<link name="WEIGHT-1KG-1">
<inertial>
<origin xyz="-1.00000000003e-06 1.46e-05 -1e-06" rpy="0 0 0"/>
<mass value="1.00161"/>
<inertia ixx="0.0010891" ixy="3.14425e-08" ixz="0.0" iyy="0.00108866" iyz="4.73842e-08" izz="0.00213553"/>
</inertial>
</link>
<joint name="chest_weight_2" type="fixed">
<origin xyz="0.150750000191 0.0955 0" rpy="1.57079632679 0 -1.57079632679"/>
<parent link="chest"/>
<child link="WEIGHT-1KG-1"/>
<dynamics damping="0.1"/>
</joint>
<gazebo>
<plugin name="controlboard_torso" filename="libgazebo_yarp_controlboard.so">
<yarpConfigurationFile>model://iCubHeidelberg01_model/conf/gazebo_iCubHeidelberg01_torso.ini</yarpConfigurationFile>
</plugin>
<plugin name="controlboard_right_leg" filename="libgazebo_yarp_controlboard.so">
<yarpConfigurationFile>model://iCubHeidelberg01_model/conf/gazebo_iCubHeidelberg01_right_leg.ini</yarpConfigurationFile>
</plugin>
<plugin name="controlboard_left_leg" filename="libgazebo_yarp_controlboard.so">
<yarpConfigurationFile>model://iCubHeidelberg01_model/conf/gazebo_iCubHeidelberg01_left_leg.ini</yarpConfigurationFile>
</plugin>
<plugin name="apply_external_wrench" filename="libgazebo_yarp_externalwrench.so">
<robotNamefromConfigFile>model://iCubHeidelberg01_model/conf/gazebo_iCubHeidelberg01_robotname.ini</robotNamefromConfigFile>
</plugin>
</gazebo>
<gazebo reference="WEIGHT-1KG-4">
<visual>
<material>
<ambient>0.2666668 0.2666668 0.2666668 1.0</ambient>
<diffuse>0.56666695 0.56666695 0.56666695 1.0</diffuse>
<specular>0.6000003 0.6000003 0.6000003 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="WEIGHT-1KG-3">
<visual>
<material>
<ambient>0.2666668 0.2666668 0.2666668 1.0</ambient>
<diffuse>0.56666695 0.56666695 0.56666695 1.0</diffuse>
<specular>0.6000003 0.6000003 0.6000003 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="WEIGHT-1KG-5">
<visual>
<material>
<ambient>0.2666668 0.2666668 0.2666668 1.0</ambient>
<diffuse>0.56666695 0.56666695 0.56666695 1.0</diffuse>
<specular>0.6000003 0.6000003 0.6000003 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="WEIGHT-1KG">
<visual>
<material>
<ambient>0.2666668 0.2666668 0.2666668 1.0</ambient>
<diffuse>0.56666695 0.56666695 0.56666695 1.0</diffuse>
<specular>0.6000003 0.6000003 0.6000003 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="WEIGHT-1KG-2">
<visual>
<material>
<ambient>0.2666668 0.2666668 0.2666668 1.0</ambient>
<diffuse>0.56666695 0.56666695 0.56666695 1.0</diffuse>
<specular>0.6000003 0.6000003 0.6000003 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="WEIGHT-1KG-1">
<visual>
<material>
<ambient>0.2666668 0.2666668 0.2666668 1.0</ambient>
<diffuse>0.56666695 0.56666695 0.56666695 1.0</diffuse>
<specular>0.6000003 0.6000003 0.6000003 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="l_leg_ft_sensor">
<sensor name="l_leg_ft_sensor" type="force_torque">
<always_on>1</always_on>
<update_rate>100</update_rate>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
</gazebo>
<sensor name="l_leg_ft_sensor" type="force_torque">
<parent joint="l_leg_ft_sensor"/>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
<gazebo reference="r_leg_ft_sensor">
<sensor name="r_leg_ft_sensor" type="force_torque">
<always_on>1</always_on>
<update_rate>100</update_rate>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
</gazebo>
<sensor name="r_leg_ft_sensor" type="force_torque">
<parent joint="r_leg_ft_sensor"/>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
<gazebo reference="l_foot_ft_sensor">
<sensor name="l_foot_ft_sensor" type="force_torque">
<always_on>1</always_on>
<update_rate>100</update_rate>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
</gazebo>
<sensor name="l_foot_ft_sensor" type="force_torque">
<parent joint="l_foot_ft_sensor"/>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
<gazebo reference="r_foot_ft_sensor">
<sensor name="r_foot_ft_sensor" type="force_torque">
<always_on>1</always_on>
<update_rate>100</update_rate>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
</gazebo>
<sensor name="r_foot_ft_sensor" type="force_torque">
<parent joint="r_foot_ft_sensor"/>
<force_torque>
<frame>child</frame>
<measure_direction>child_to_parent</measure_direction>
</force_torque>
</sensor>
<gazebo reference="chest">
<sensor name="imu_frame" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<pose>-0.0169999998093 0.100500000006 -0.0380999999838 -3.14159265359 -0.0 0.0</pose>
<plugin name="iCub_yarp_gazebo_plugin_IMU" filename="libgazebo_yarp_imu.so">
<yarpConfigurationFile>model://iCubGenova02/conf/inertial.ini</yarpConfigurationFile>
</plugin>
</sensor>
</gazebo>
<sensor name="imu_frame" type="imu">
<parent link="chest"/>
<origin rpy="-3.14159265359 -0.0 0.0" xyz="-0.0169999998093 0.100500000006 -0.0380999999838"/>
</sensor>
<gazebo>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
</gazebo>
</robot>
No error message is displayed
That's strange on my PC this command line executed in the test folder generates the correct model. As an example this is the root_link
:
<inertial>
<origin xyz="0.0251137 0.000104218 -0.0437451" rpy="1.57079632679 0 -1.57079632679"/>
<mass value="5.1504"/>
<inertia ixx="0.0140911" ixy="6.63933e-05" ixz="-8.71849e-05" iyy="0.0205529" iyz="-0.00172034" izz="0.0252712"/>
</inertial>
<visual>
<origin xyz="-0.0364 0 0.032" rpy="1.57079632679 0 -1.57079632679"/>
<geometry>
<mesh filename="model://iCubHeidelberg01_model/dae_meshes/sim_root_link.dae" scale="0.001 0.001 0.001"/>
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
<collision>
<origin xyz="-0.0364 0 0.032" rpy="1.57079632679 0 -1.57079632679"/>
<geometry>
<mesh filename="model://iCubHeidelberg01_model/dae_meshes/sim_root_link.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
The only warning I get is the following:
Inertia: [[ 3.00000000e-04 -7.03830522e-06 -4.61427517e-04]
[ -7.03830522e-06 3.00000000e-04 -6.20681339e-05]
[ -4.61427517e-04 -6.20681339e-05 3.00000000e-04]] is not a valid Inertia matrix because it has negative inertias on the principal axis.
Warning: inertia matrix for link r_foot is not physically consistent.
I have to check the dependencies.
Do you have any warning about the meshes?
Also the last build seems fine.
I fear that some dependency has been modified. Probably @drdanz can restart the build on Travis and we should be able to see if this is the case.
I tried uninstalling and reinstalling everything, but still the same. Here is my terminal output:
gnava@iiticublap120 ~/Software/github/robotology/simmechanics-to-urdf/test (master) $ simmechanics_to_urdf LEGS_MECHANISM.xml --yaml legs_simmechanics_options.yaml --csv-joints joint_parameters.csv --output xml --outputfile testurdf.urdf
/usr/local/lib/python2.7/dist-packages/simmechanics_to_urdf-0.2-py2.7.egg/simmechanics_to_urdf/firstgen.py:289: YAMLLoadWarning: calling yaml.load() without Loader=... is deprecated, as the default Loader is unsafe. Please read https://msg.pyyaml.org/load for full details.
Inertia: [[ 3.00000000e-04 -7.03830522e-06 -4.61427517e-04]
[-7.03830522e-06 3.00000000e-04 -6.20681339e-05]
[-4.61427517e-04 -6.20681339e-05 3.00000000e-04]] is not a valid Inertia matrix because it has negative inertias on the principal axis.
there is a warning concerning the YAML loader too.
I fix easily the warning by changing the yaml.load
here to yaml.safe_load
, but still the issue is there.
Ok, I did a bit of analysis of the problem. it seems that the visual
and collision
elements are generated correctly by https://github.com/robotology/simmechanics-to-urdf/blob/master/simmechanics_to_urdf/firstgen.py. In fact, I added the line
print(visual)
right before this command and I can see the visual elements printed on the terminal with no errors:
geometry:
filename: model://iCubHeidelberg01_model/dae_meshes/sim_root_link.dae
scale:
- 0.001
- 0.001
- 0.001
material:
color:
rgba:
- 0
- 1
- 0
- 1
name: green
texture: None
origin:
rpy:
- 1.5707963267948961
- 0
- -1.5707963267948961
xyz:
- -0.036399999999999995
- 0
- 0.032
This made me tought that the culprit should be the class urdf.Link()
from urdf_parser_py. I checked in their github repo and - surprise! there is an issue about exactly this problem! See ros/urdf_parser_py#42
I will try to revert back to previous commits of the urdf_parser_py
and I'll add more details.
I fixed the issue! the problem was due to multiple causes, all of them related to the urdf_parser_py
:
-
there is a problem using the
urdf.Link
class for setting visual and collision elements. I moved to thefork
associated with this PR: ros/urdf_parser_py#47 -
there was a conflict between the
urdf.py
class installed by theurdf_parser_py
repo and the same class that came along with the ros installation. Therefore I was actually always using the wrong class, that was located in/opt/ros/melodic/lib/python2.7/dist-packages/urdf_parser_py
, rather than the one coming from the aforementioned PR, located in/usr/local/lib/python2.7/dist-packages/urdf_parser_py
. Renaming theurdf_parser_py
folder located in/opt/ros/....
tourdf_parser_py_OLD
allowed me to point the correct class, and this fixed the issue!
See the first link of the urdf:
<link name="root_link">
<inertial>
<origin xyz="-0.0026057700000000003 2.6285900000000003e-06 -0.0551054" rpy="0 0 0"/>
<mass value="1.73671"/>
<inertia ixx="0.102027" ixy="3.49564e-06" ixz="-0.000139376" iyy="0.0882212" iyz="3.14137e-06" izz="0.187815"/>
</inertial>
<visual>
<origin xyz="0 0 -0.03475" rpy="0 0 0"/>
<geometry>
<mesh filename="sim_drone.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.03475" rpy="0 0 0"/>
<geometry>
<mesh filename="sim_drone.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
closing the issue.
Thanks @gabrielenava for this check! ๐
In order to catch this kind of issues earlier probably could be useful to have nightly builds that take place automatically and specific unit test that fail if the generated urdf
model is not well formed.
In Travis we can use Cron Jobs. If we agree we can open a dedicated issue to discuss the implementation of this feature.
@fiorisi
Fine to me!
Thanks @gabrielenava for the in-depth debugging.
closing the issue.
I am not sure why we are closing the issue. As far as I understand, if anyone installs the simmechanics-to-urdf
following the documentation contained in the README, it will be affected by the issue, right? The idea is to track this general issue in #36 ?
@traversaro I agree. Considering the title of the issue probably we should keep it open.
Nevertheless, following your comment The idea is to track this general issue in #36 ?
probably we can keep only one.
There is also a link to the solution explained here.