Can't load meshes correcly
So I am trying to import a robot into gazebo and it doesn't work, so I cut down my model to just the frame and the that doesn't even work. Here is the sdf file I am trying to load:
<?xml version='1.0'?>
<sdf version='1.4'>
<model name='rbe_500_model'>
<link name='base_link'>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>-0.264565 -0.0662113 0.0664452 0 -0 0</pose>
<mass>1.58034</mass>
<inertia>
<ixx>0.166304</ixx>
<ixy>-0.0400234</ixy>
<ixz>-0.0244204</ixz>
<iyy>0.181894</iyy>
<iyz>-0.00669269</iyz>
<izz>0.191948</izz>
</inertia>
</inertial>
<collision name='base_link_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model:$(find rbe_500_model)/meshes/base_link.STL</uri>
</mesh>
</geometry>
</collision>
<visual name='base_link_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model:$(find rbe_500_model)/meshes/base_link.STL</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>
I get these errors when I try to spawn the model
Error [MeshShape.cc:64] No mesh specified
Error [Visual.cc:2072] No mesh specified
any idea what I am doing wrong?
Asked by AlphaOne on 2013-11-26 15:23:18 UTC
Answers
You mesh imports are incorrect. To import meshes from ROS packages in Gazebo, you need to use the syntax:
<uri>model://my_package/meshes/foo.STL</uri>
For Gazebo to find your package, you also need to include the code block below in your package.xml
. See this answer for more information.
<export>
<!-- gazebo_ros_paths_plugin automatically adds these to
GAZEBO_PLUGIN_PATH and GAZEBO_MODEL_PATH when you do this export inside
the package.xml file. You can than use URIs of type model://my_package/stuff. -->
<gazebo_ros
gazebo_plugin_path="${prefix}/lib"
gazebo_model_path="${prefix}/.." />
</export>
Asked by matwilso on 2016-12-22 19:38:01 UTC
Comments
Hi, I got the same issue for two interns, they can't load gzclient without an error about the 3D files not found with the path on the gzserver on a remote server. Both of them use roslaunch files to start . They use a custom version of husky robot and hector_quadcopter.
Very strange.
Asked by Tomlogan on 2020-07-29 10:06:05 UTC
Comments
maybe the 'find' command is not supported, (meaning "$(find rbe_500_model)"), or you are missing the STL files. You can try it by adding the rbe_500_model folder to the gazebo model path. Here is a tutorials that explains it in more detail: 'http://gazebosim.org/wiki/Tutorials/1.9/build_robot/attach_meshes'
Asked by AndreiHaidu on 2013-11-27 04:23:13 UTC