Unable to spawn the urdf model
I am trying to follow the tutorial https://gazebosim.org/docs/garden/spawn_urdf . I have a URDF file which works fine in Rviz2.
While following the tutorial, I run the command ign gazebo empty.sdf
in one terminal. After running this command, I get an empty window as shown in the tutorial. Now, I open another terminal in the directory where the urdf file is and run the command gz service -s /world/empty/create --reqtype gz.msgs.EntityFactory --reptype gz.msgs.Boolean --timeout 1000 --req 'sdf_filename: "robot_new.urdf", name: "urdf_model"'
, I get two errors in the terminal window which are
Error [parser.cc:729] Error finding file [robot_new.urdf]
[Err] [UserCommands.cc:1138] Error Code 1: Msg: Unable to read file:robot_new.urdf
The urdf file is
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot_x.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="robot">
<!-- Specify some standard inertial calculations https://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<!-- These make use of xacro's mathematical functionality -->
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<material name="orange">
<color rgba="1 0.3 0.1 1"/>
</material>
<material name="blue">
<color rgba="0.2 0.2 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- BASE LINK-->
<link name="base_link">
</link>
<!-- CHASSIS LINK -->
<link name="chassis">
<visual>
<geometry>
<box size="0.3 0.3 0.15"/>
</geometry>
<origin xyz="0.15 0 0.075"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="0.3 0.3 0.15"/>
</geometry>
<origin xyz="0.15 0 0.075"/>
<material name="white"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.15 0 0.075"/>
<mass value="0.5"/>
<inertia ixx="0.004687499999999999" ixy="0.0" ixz="0.0" iyy="0.004687499999999999" iyz="0.0" izz="0.0075"/>
</inertial>
</link>
<!-- BASE_LINK CHASSIS JOINT-->
<joint name="chassis_joint" type="fixed">
<parent link="base_link"/>
<child link="chassis"/>
<origin xyz="-0.1 0 0"/>
</joint>
<!-- LEFT WHEEL LINK -->
<link name="left_wheel">
<visual>
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
<material name="blue"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.1"/>
<inertia ixx="7.583333333333335e-05" ixy="0.0" ixz="0.0" iyy="7.583333333333335e-05" iyz="0.0" izz="0.00012500000000000003"/>
</inertial>
</link>
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<axis xyz="0 0 1"/>
<origin rpy="-1.57075 0 0" xyz="0 0.175 0"/>
</joint>
<!-- RIGHT WHEEL LINK -->
<link name="right_wheel">
<visual>
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
<material name="blue"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.1"/>
<inertia ixx="7.583333333333335e-05" ixy="0.0" ixz="0.0" iyy="7.583333333333335e-05" iyz="0.0" izz="0.00012500000000000003"/>
</inertial>
</link>
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<axis xyz="0 0 -1"/>
<origin rpy="1.57075 0 0" xyz="0 -0.175 0"/>
</joint>
<!-- CASTER WHEEL JOINT -->
<joint name="caster_wheel_joint" type="fixed">
<parent link="chassis"/>
<child link="caster_wheel"/>
<origin xyz="0.24 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material name="black"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.1"/>
<inertia ixx="0.00010000000000000005" ixy="0.0" ixz="0.0" iyy="0.00010000000000000005" iyz="0.0" izz="0.00010000000000000005"/>
</inertial>
</link>
</robot>
I even tried by converting the urdf file to sdf format and then entering the sdf filename, but I still get those same errors. So, how do i remove those errors and spawn the urdf file in gazebo.
Using Gazebo - Fortress
ubuntu 22.04
Asked by Sahil Goyal on 2022-10-20 11:16:51 UTC
Answers
The issue is that the gazebo server is the one that looks for the file new_robot.urdf
, which was started in the other terminal and likely has a different CWD
than the terminal you used gz service
in. Since you've provided a relative path, gazebo is going to look for the file relative to it's CWD
. One way to solve this to provide an absolute path to new_robot.urdf
. Another way would be to add the directory that contains new_robot.urdf
into the IGN_GAZEBO_RESOURCE_PATH
(GZ_SIM_RESOURCE_PATH
for Garden) environment variable (see https://gazebosim.org/api/sim/6/resources.html)
Asked by azeey on 2022-10-28 15:49:36 UTC
Comments
Even after providing the full path to the file, it does not work.
Regarding adding the directory, I added the line in the end in .bashrc export GZ_SIM_RESOURCE_PATH="$GZ_SIM_RESOURCE_PATH:/path/to/required/directory"
, but still it does not work.
In both the cases, I get the same error.
Asked by Sahil Goyal on 2023-01-03 07:37:19 UTC
If you are using Gazebo Fortress, you should be using IGN_GAZEBO_RESOURCE_PATH
and your service call should be ign service -s /world/empty/create --reqtype ignition.msgs.EntityFactory --reptype ignition.msgs.Boolean --timeout 1000 --req 'sdf_filename: "robot_new.urdf", name: "urdf_model"'
. https://gazebosim.org/docs/garden/migration_from_ignition might be helpful here.
Asked by azeey on 2023-01-04 11:22:51 UTC
Actually, this question was asked a lot earlier. That time, I had Ign-fortress but now I had installed garden from source after giving up on fortress that time.
Also, the issue was using ~
in the path specified for the urdf file. After, I replaced ~
with /home/sahil
, it worked fine.
Asked by Sahil Goyal on 2023-01-04 23:20:38 UTC
Comments