[collada to urdf] Segmentation fault in gazebo (Ubuntu 18.04)
Naoki-Hiraoka opened this issue · 2 comments
When I spawned urdf model converted from collada into gazebo (melodic, ubuntu18.04), I got Segmentation fault (core dumped).
I did not get this Segmentation fault with urdf models converted in kinetic (ubuntu 16.04).
Thread 39 "gzserver" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fff1ffff700 (LWP 23344)]
0x00007ffff6a0aa76 in std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::find_first_not_of(char, unsigned long) const ()
from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
(gdb) Segmentation fault (core dumped)
[gazebo_gui-3] process has died [pid 23197, exit code 139, cmd /opt/ros/melodic/lib/gazebo_ros/gzclient __name:=gazebo_gui __log:=/home/hiraoka/.ros/log/d975cdd0-31f4-11ea-99d9-5c514f34f247/gazebo_gui-3.log].
log file: /home/hiraoka/.ros/log/d975cdd0-31f4-11ea-99d9-5c514f34f247/gazebo_gui-3*.log
(gdb) bt
#0 0x00007ffff6a0aa76 in std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::find_first_not_of(char, unsigned long) const ()
at /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#1 0x00007ffff6ec6acf in ()
at /usr/lib/x86_64-linux-gnu/libgazebo_common.so.9
#2 0x00007ffff6ed9a63 in gazebo::common::ColladaLoader::LoadPolylist(TiXmlElement*, ignition::math::v4::Matrix4<double> const&, gazebo::common::Mesh*) ()
at /usr/lib/x86_64-linux-gnu/libgazebo_common.so.9
#3 0x00007ffff6edc859 in gazebo::common::ColladaLoader::LoadGeometry(TiXmlElement*, ignition::math::v4::Matrix4<double> const&, gazebo::common::Mesh*) ()
at /usr/lib/x86_64-linux-gnu/libgazebo_common.so.9
#4 0x00007ffff6ede830 in gazebo::common::ColladaLoader::LoadNode(TiXmlElement*, gazebo::common::Mesh*, ignition::math::v4::Matrix4<double> const&) ()
at /usr/lib/x86_64-linux-gnu/libgazebo_common.so.9
#5 0x00007ffff6edef89 in gazebo::common::ColladaLoader::LoadScene(gazebo::common::Mesh*) () at /usr/lib/x86_64-linux-gnu/libgazebo_common.so.9
#6 0x00007ffff6edf4b0 in gazebo::common::ColladaLoader::Load(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) ()
at /usr/lib/x86_64-linux-gnu/libgazebo_common.so.9
#7 0x00007ffff6efe89a in gazebo::common::MeshManager::Load(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) ()
at /usr/lib/x86_64-linux-gnu/libgazebo_common.so.9
#8 0x00007ffff5abee8b in gazebo::physics::MeshShape::Init() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#9 0x00007ffff59d54c4 in gazebo::physics::ODEMeshShape::Init() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#10 0x00007ffff5a65762 in gazebo::physics::Collision::Init() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#11 0x00007ffff5aac27e in gazebo::physics::Link::Init() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#12 0x00007ffff59d30ae in gazebo::physics::ODELink::Init() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#13 0x00007ffff5ac9a9e in gazebo::physics::Model::Init() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#14 0x00007ffff5b13727 in gazebo::physics::World::ProcessFactoryMsgs() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#15 0x00007ffff5b1945d in gazebo::physics::World::ProcessMessages() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#16 0x00007ffff5b1ad84 in gazebo::physics::World::Step() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#17 0x00007ffff5b1b1cd in gazebo::physics::World::RunLoop() ()
at /usr/lib/x86_64-linux-gnu/libgazebo_physics.so.9
#18 0x00007ffff69a166f in () at /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#19 0x00007ffff5dfd6db in start_thread (arg=0x7fff1ffff700)
at pthread_create.c:463
#20 0x00007ffff63fc88f in clone ()
at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95
I think this is because of assimp.
This commit of assimp assimp/assimp@36e53b7#diff-758737a587ca204dec82e47c452466d2
changed the output mesh
ftom
<mesh>
...
<vertices id="meshId0-vertices">
<input semantic="POSITION" source="#meshId0-positions" />
<input semantic="NORMAL" source="#meshId0-normals" />
</vertices>
<polylist count="11" material="defaultMaterial">
<input offset="0" semantic="VERTEX" source="#meshId0-vertices" />
<vcount>3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 17 18 15 19 20 21 21 22 19 23 24 25 26 27 28 </p>
</polylist>
</mesh>
to
<mesh>
...
<vertices id="meshId0-vertices">
<input semantic="POSITION" source="#meshId0-positions" />
</vertices>
<polylist count="11" material="defaultMaterial">
<input offset="0" semantic="VERTEX" source="#meshId0-vertices" />
<input offset="0" semantic="NORMAL" source="#meshId0-normals" />
<vcount>3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 17 18 15 19 20 21 21 22 19 23 24 25 26 27 28 </p>
</polylist>
</mesh>
This modification may cause index out of range
at this line of gazebo.
https://bitbucket.org/osrf/gazebo/src/a3eb517b0fa58d230f87e5dadf5976b1d4f1d3c9/gazebo/common/ColladaLoader.cc?fileviewer=file-view-default#lines-1548
Thanks for the report, and what looks like a thorough investigation of the issue.
It looks to me like this is a bug in Gazebo itself, so I encourage you to open an issue at https://bitbucket.org/osrf/gazebo/issues . I'm going to close this report out, but feel free to reopen if you still think it is something that collada_urdf should change.
Thank you for your kind guidance.
I opened an issue https://bitbucket.org/osrf/gazebo/issues/2682 .