Unable to find uri[model://my1stmodel]
Hello,
I have a problem visualizing my custom model in Gazebo using ROS. The model is working fine if I manually add it by adding a path and dragging it from the model's tab.
To reproduce the problem step by step (using theconstructsim tutorial here, I created a simple rospack just to visualize the custom model. The directory looks like:
├── CMakeLists.txt
├── package.xml
├── launch
│ └── my_world.launch
├── models
│ └── my1stmodel
│ ├── model.config
│ └── model.sdf
└── world
└── empty_world.world
In the launch file:
<?xml version="1.0" encoding="UTF-8" ?>
<launch>
<!-- overwriting these args -->
<arg name="debug" default="false" />
<arg name="gui" default="true" />
<arg name="pause" default="false" />
<arg name="world" default="$(find test_simulations)/world/empty_world.world" />
<!-- include gazebo_ros launcher -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world)" />
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg pause)" />
<arg name="use_sim_time" value="true" />
</include>
</launch>
The model.config file:
<?xml version="1.0"?>
<model>
<name>My first model</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>
<author>
<name>Your name</name>
<email>your@email.com</email>
</author>
<description>
My first model for gazebo
</description>
And finally the model.sdf file:
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="my1stmodel">
<static>false</static>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>3 2 5</size>
</gox>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<geometry>
<box>
<size>3 2 5</size>
</gox>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>
</model>
However, I cannot visualize the model and I get Unable to find uri[model://my1stmodel]
when I call the launch file. After a deep search the whole day, I saw that export GAZEBO_MODEL_PATH=[...]/models:$GAZEBO_MODEL_PATH
might have been added. I tried and didn't work. Then I've found people saying this shouldn't work for Gazebo on ROS.
Then I tried adding manually, like adding the path to the models tab and dragging from there, and then saving the world (with save as). I was hoping to see that I missed some folder or name error while calling the model. What I see is that the Gazebo-exported world has also added my custom model in the same way. So, I am solutionless at the moment. I can see that I cannot call the model properly but I don't see where I am wrong.
Thank you in advance
Asked by TheClem on 2021-02-21 12:22:27 UTC
Comments