ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
so by looking at the iris.sdf file, I can see that you've pasted URDF into the .sdf file. If we take a look at the following two pieces of code we can see what I mean:
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
This first part is from line 80-84, the piece you've added.
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
This second part is from line 89-100, the part that already existed.
The way you write down sdf vs urdf is different, so your piece of code should look like this:
<inertial>
<pose frame=''>0 0 0 0 0 0</pose>
<mass>1e-05</mass>
<inertia>
<ixx>1e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-06</iyy>
<iyz>0</iyz>
<izz>1e-06</izz>
</inertia>
</inertial>
The same goes for all the lines you've added (56-85).
To get to the actual error you're seeing Required attribute[name] in element[collision] is not specified in SDF
that's from line 65-70.
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_link} ${camera_link} ${camera_link}"/>
</geometry>
</collision>
The collision requires a name, so line 65 should have been:
<collision name="camera_link_collision">
There are probably more errors, but like I said, I think you get those errors because you just simply add URDF in a .sdf file. I know that the other way around, you can fix this by adding
<gazebo reference="${link_name}">
...
</gazebo>
around the piece of sdf. I don't know if there is a URDF equivalent or if you should just rewrite it to sdf.
2 | No.2 Revision |
so by looking at the iris.sdf file, I can see that you've pasted URDF into the .sdf file. If we take a look at the following two pieces of code we can see what I mean:
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
This first part is from line 80-84, the piece you've added.
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
This second part is from line 89-100, the part that already existed.
The way you write down sdf vs urdf is different, so your piece of code should look like this:
<inertial>
<pose frame=''>0 0 0 0 0 0</pose>
<mass>1e-05</mass>
<inertia>
<ixx>1e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-06</iyy>
<iyz>0</iyz>
<izz>1e-06</izz>
</inertia>
</inertial>
The same goes for all the lines you've added (56-85).
To get to the actual error you're seeing Required attribute[name] in element[collision] is not specified in SDF
that's from line 65-70.
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_link} ${camera_link} ${camera_link}"/>
</geometry>
</collision>
The collision requires a name, so line 65 should have been:
<collision name="camera_link_collision">
There are probably more errors, but like I said, I think you get those errors because you just simply add URDF in a .sdf file. I know that the other way around, you can fix this by adding
<gazebo reference="${link_name}">
...
</gazebo>
around the piece of sdf. I don't know if there is a URDF equivalent or if you should just rewrite it to sdf.
EDIT because I forgot: http://sdformat.org/spec might be an interesting site to take a look at.