Closed astumpf closed 2 years ago
Can you provide the urdf you used so as to identify which commit actually broke the behavior?
Unfortunately I cannot disclose our internal URDF. But this issue is related to the physics node of the root link of the robot. When the root link (i.e. base_link) is a fixed link and you attach an IMU to it, you will run in this problem.
Basically, it looks like this
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="my_robot">
<link name="base_link">
<inertial>
<mass value="0.001" />
<inertia ixx="1e-06" ixy="0" ixz="0" iyy="1e-06" iyz="0" izz="1e-06" />
<origin xyz="0 0 0" rpy="0 0 0" />
</inertial>
</link>
<link name="substructure_link">
<visual>
<origin xyz="0 0 0" rpy="3.14159265358979 0 0" />
</visual>
<inertial>
<mass value="19.071313858032227" />
<inertia ixx="0.63005133573409289" ixy="-0.00076282161535707747" ixz="0.0017282156658180987" iyy="0.37519285561891186" iyz="-0.0038628958352941107" izz="0.63759031368070762" />
<origin rpy="0 0 0" xyz="0.00979819299726629 0.00408222060576725 0.130251498956635" />
</inertial>
</link>
<joint name="substructure_joint" type="fixed">
<parent link="base_link" />
<child link="substructure_link" />
<origin xyz="0 0 -0.444601164826685" rpy="0 0 0" />
</joint>
<!-- some further robot urdf connected substructure_link goes here -->
<!-- IMU plugin -->
<gazebo reference="base_link">
<plugin name="base_imu" filename="libgazebo_ros_imu.so">
<alwaysOn>true</alwaysOn>
<bodyName>base_link</bodyName>
<topicName>/gazebo/sensor/imu</topicName>
<serviceName>/gazebo/sensor/imu_service</serviceName>
<gaussianNoise>0.0</gaussianNoise>
<updateRate>100</updateRate>
</plugin>
</gazebo>
</robot>
Generating the PROTO from your example I don't run in the issue you mention, the parent's Physics node appears to be defined correctly:
#VRML_SIM R2022a utf8
# license: Apache License 2.0
# license url: http://www.apache.org/licenses/LICENSE-2.0
# This is a proto file for Webots for the test
# Extracted from: /home/daniel/urdf2webots/test.urdf
PROTO test [
field SFVec3f translation 0 0 0
field SFRotation rotation 0 0 1 0
field SFString name "test" # Is `Robot.name`.
field SFString controller "void" # Is `Robot.controller`.
field MFString controllerArgs [] # Is `Robot.controllerArgs`.
field SFString customData "" # Is `Robot.customData`.
field SFBool supervisor FALSE # Is `Robot.supervisor`.
field SFBool synchronization TRUE # Is `Robot.synchronization`.
field SFBool selfCollision FALSE # Is `Robot.selfCollision`.
]
{
Robot {
translation IS translation
rotation IS rotation
controller IS controller
controllerArgs IS controllerArgs
customData IS customData
supervisor IS supervisor
synchronization IS synchronization
selfCollision IS selfCollision
children [
InertialUnit {
name "/gazebo/sensor/imu inertial"
}
Accelerometer {
name "/gazebo/sensor/imu accelerometer"
}
Gyro {
name "/gazebo/sensor/imu gyro"
}
Compass {
name "/gazebo/sensor/imu compass"
}
Solid {
translation 0.000000 0.000000 -0.444601
rotation 0.000000 0.000000 1.000000 0.000000
children [
Transform {
translation 0.000000 0.000000 0.000000
rotation 1.000000 0.000000 0.000000 3.141593
children [
Shape {
appearance PBRAppearance {
baseColor 0.500000 0.500000 0.500000
transparency 0.000000
roughness 1.000000
metalness 0
emissiveColor 0.000000 0.000000 0.000000
}
geometry Box {
size 1.0 1.0 1.0
}
}
]
}
]
name "substructure_link"
physics Physics {
density -1
mass 19.071314
centerOfMass [ 0.009798 0.004082 0.130251 ]
inertiaMatrix [
6.300513e-01 3.751929e-01 6.375903e-01
-7.628216e-04 1.728216e-03 -3.862896e-03
]
}
}
]
name IS name
physics Physics {
density -1
mass 0.001000
centerOfMass [ 0.000000 0.000000 0.000000 ]
inertiaMatrix [
1.000000e-06 1.000000e-06 1.000000e-06
0.000000e+00 0.000000e+00 0.000000e+00
]
}
}
}
Thanks for your quick response. I will check this again on our side and let you know. Maybe I can generate a minimal example. Maybe this problem occurs if the robot has a structure like this:
base_link (fixed) -> sub_link (fixed) -> another_sub_link (fixed) -> joint_1
Thank you, yes if you could provide a minimal example that reproduces the issue that would help a lot
While generating a minimal example, I figured out how to reproduce (but not fix) this issue.
Minimal example that will generate a physics node to the base_link:
<?xml version="1.0" encoding="utf-8"?>
<robot name="test" xmlns:xacro="http://ros.org/wiki/xacro">
<link name="base_link">
<inertial>
<mass value="0.1" />
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
</inertial>
</link>
<link name="limb1_link">
<inertial>
<mass value="0.1" />
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
</inertial>
</link>
<joint name="limb1_joint" type="fixed">
<parent link="base_link" />
<child link="limb1_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<link name="limb2_link">
<!-- removing inertial here -> prevents to generate physics node at base!!! -->
<inertial>
<mass value="0.1" />
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
</inertial>
</link>
<joint name="limb2_joint" type="fixed">
<parent link="base_link" />
<child link="limb2_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
</robot>
If you remove the inertial part (massless fixed link) from a single link (i.e. limb2_link), it will not generate a physics node to the base_link.
Thank you, I can indeed reproduce the behavior you mention however it appears to be broken only in the master branch, in the develop one this simplified example works as intended. So I assume it was fixed already (intentionally or otherwise). If you could confirm me that indeed the develop branch works for your non-minimal example I will find what changed and backport it.
I can confirm that in develop
this issue does not appear.
Since 2d620813c999c38be73f4fbd5d49fdb031ed8b0a a major change was applied that prevents to attach a physics node to the root element (base). I've also noticed that the new version does generate a lot less links, I guess there is some kind of simplifications regarding static links involved. However, this breaks any current usage with Gyro sensor (parsed from IMU elements from URDF). Now all Gyro nodes are complaining for a missing physics-enabled parent node.
Diffing the previously generated proto file with the new file reveals following change:
Readding these lines, fixes the Gyro problem. Therefore, I'm wondering how to fix that issue in the convertor.