-
Notifications
You must be signed in to change notification settings - Fork 43
Description
ToDo: Review the mesh import to MARS
Obj mesh orientations are interpreted not consistently, I guess this comes from the old default how they were exported from blender by default.
I had a look on the behaviour of pyBullet, Gazebo, rock-roboviz and MARS using the doc/a test model; and also into the mesh formats.
This I will explain deeper in the following.
As described below the most simulators and mesh formats are consistent, I suggest the following that MARS should be adapted to interpret obj (bobj), stl and dae accordingly.
Test data
I created the mesh above in blender to identify the axes when loaded. (Color coding: RGB = XYZ)The length and points of the arms display the axis by their length and vertices at their end: x=1, y=2, z=3
This mesh is included in the following URDF:
<robot name="mesh_orientation_tester" version="1.0">
<link name="root">
<visual name="zupyforward">
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="zupyforward.dae" scale="1.0 1.0 1.0"/>
</geometry>
</visual>
<collision name="zupyforward_collision">
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="zupyforward.dae" scale="1.0 1.0 1.0"/>
</geometry>
</collision>
</link>
</robot>
The mesh I exchanged vs their DAE/STL/OBj version during testing.
Mesh formats
STL
STL saves vertices in the following format:
facet normal -1.000000 0.000000 0.000000
outer loop
vertex 0.000000 0.000000 3.000000
vertex 0.000000 2.000000 0.000000
vertex 1.000000 0.000000 0.000000
endloop
When using the convention Z is Up and Y is Forward, the STL base frame has the same orientation as intended by the mesh. See the format example which shows a face that was created with vertices on all axis with different distances from the origin: x = 1 y =2 z =3.
Wavefront OBJ
OBJ saves vertices in the following format:
o zupyforward
v 0.000000 2.000000 0.000000
v 1.000000 0.000000 0.000000
v 0.000000 0.000000 3.000000
...
Equally to STL the OBJ origin is the same as the origin during creation when using the export convention Z is Up and Y is Forward.
Collada DAE
In DAE vertices are saved in the following format:
...
<library_geometries>
<geometry id="zupyforward-mesh" name="zupyforward">
<mesh>
<source id="zupyforward-mesh-positions">
<float_array id="zupyforward-mesh-positions-array" count="255">0.000000 2.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 3.000000 ...</float_array>
<technique_common>
<accessor source="#zupyforward-mesh-positions-array" count="85" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
...
Again DAE uses the same origin as STL and OBJ.
Expectation
As URDF gives transformations from root->link->mesh the orientation of the mesh is clearly defined. I'd expect that the mesh will placed accordingly.
As the test URDF, presented above, has only zero transformations and the mesh is oriented in all tested mesh formats without any orientation, I'd expect that in all simulators the X-arm of the mesh will point in X-direction, Y-arm in Y-direction and Z-arm in Z-direction.
Testing the simulators
pyBullet
import pybullet as pb
pb.connect(pb.GUI)
pb.loadURDF("mesh_orientation_tester.urdf")
PyBullet fulfils the expectation for all formats.
MARS
mars_app -s mesh_orientation_tester.urdf
In the images X is pointing in to the right, Y up and Z into the screen. MARS fulfils the expectation for STL and DAE, but obj seems to be loaded differently. Here showing only the visual representation.
Further bugs
STL collisions #98
Please note that MARS seems to load STL Meshes also differently depending on whether the mesh is loaded as visual or collision (see also #98). I reproduced this issue
DAE Collisions
Loading the URDF with DAE as a collision mesh was not possible and threw a segmentation fault.
gdb --args mars_app -s mesh_orientation_tester.urdf
returned:
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
Gtk-Message: 10:14:15.389: Failed to load module "canberra-gtk-module"
Active locale (LC_ALL): [OK]
config file not found: ${AUTOPROJ_CURRENT_ROOT}/install/configuration/mars_default/mars_Preferences.yaml
MARS::loadCoreLibs: Loading default core libraries...
info: Simulator: no console loaded. output to stdout!
EntityFactory: registering factory for type 'smurf'.
EntityFactory: registering factory for type 'urdf'.
EntityFactory: registering factory for type 'particle'.
info: smurf_loader: added SMURF loader to loadCenter
config file not found: ${AUTOPROJ_CURRENT_ROOT}/install/configuration/mars_default/configWindows.yml
osg_frames: load ${AUTOPROJ_CURRENT_ROOT}/install/simulation/mars/common/graphics/osg_frames/share/osg_frames/resources/frame.obj
config file not found: ${AUTOPROJ_CURRENT_ROOT}/install/configuration/mars_default/mars_Gui.yaml
config file not found: ${AUTOPROJ_CURRENT_ROOT}/install/configuration/mars_default/mars_Graphics.yaml
retina scale: 1
[New Thread 0x7fffdb4e9700 (LWP 14170)]
[New Thread 0x7fffdacd8700 (LWP 14171)]
initialized postDrawCallback
set use shader: 1 1
MARS::loadAdditionalLibs: Loading default additional libraries...
info: Simulator: console loaded. stop output to stdout!
ERROR: could not find SpaceMouse!
Do you have read permission on the /dev/input/ device?
lib_manager - NOTIFICATION (concerning optional library):
libPythonMars.so: cannot open shared object file: No such file or directory
config file not found: ${AUTOPROJ_CURRENT_ROOT}/install/configuration/mars_default/DataBrokerPlotter.yaml
config file not found: ${AUTOPROJ_CURRENT_ROOT}/install/configuration/mars_default/mars_Simulator.yaml
config file not found: ${AUTOPROJ_CURRENT_ROOT}/install/configuration/mars_default/mars_Physics.yaml
SMURFLoader::loadFile: file_extension=.urdf
Reading in ./mesh_orientation_tester.urdf...
Creating 1 simulation entities...
Loading Entity of type urdf.
SMURF::createEntity: Creating entity of type urdf
...loading urdf data from ./mesh_orientation_tester.urdf.
parsing model...
mapIndex: 1
smurfing robot: mesh_orientation_tester...
Warning: The DOM was unable to create an attribute xmlns:xsi = http://www.w3.org/2001/XMLSchema-instance at line 11.
Probably a schema violation.
Warning: The DOM was unable to create an attribute xmlns:xsi = http://www.w3.org/2001/XMLSchema-instance at line 11.
Probably a schema violation.
Thread 1 "mars_app" received signal SIGSEGV, Segmentation fault.
with the following backtrace
#0 mars::graphics::LoadDrawObject::loadGeodes (this=<optimized out>, filename=..., objname="")
at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/graphics/src/3d_objects/LoadDrawObject.cpp:131
#1 0x00007ffff1b736ca in mars::graphics::LoadDrawObject::createGeometry[abi:cxx11]() (this=0x555555f045a0) at /usr/include/c++/9/bits/basic_string.h:940
#2 0x00007ffff1b7176f in mars::graphics::DrawObject::createObject (this=0x555555f045a0, id=<optimized out>, pivot=..., sharedID=0)
at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/graphics/src/3d_objects/DrawObject.cpp:125
#3 0x00007ffff1b6960a in mars::graphics::OSGNodeStruct::OSGNodeStruct (this=0x55555644e220, g=<optimized out>, node=..., isPreview=<optimized out>, id=4)
at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/graphics/src/wrapper/OSGNodeStruct.cpp:185
#4 0x00007ffff1b36d49 in mars::graphics::GraphicsManager::addDrawObject (this=0x555555d77ce0, snode=..., activated=<optimized out>)
at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/graphics/src/GraphicsManager.cpp:899
#5 0x00007ffff2220be1 in mars::sim::NodeManager::addNode (this=0x555555675130, nodeS=0x7ffffffef830, reload=<optimized out>, loadGraphics=<optimized out>)
at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/sim/src/core/NodeManager.cpp:302
#6 0x00007ffff1f12df4 in mars::smurf::SMURF::loadNode (this=0x5555558153f0, config=...) at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/entity_generation/smurf/src/smurf.cpp:1143
#7 0x00007ffff1f14006 in mars::smurf::SMURF::load (this=0x5555558153f0) at /usr/include/c++/9/bits/stl_list.h:153
#8 0x00007ffff1f14b94 in mars::smurf::SMURF::createEntity (this=0x5555558153f0, config=...) at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/entity_generation/smurf/src/smurf.cpp:252
#9 0x00007ffff245fadd in mars::entity_generation::EntityFactoryManager::createEntity (this=0x5555557b9400, config=...) at /usr/include/c++/9/bits/basic_string.h:405
#10 0x00007ffff1c19bd3 in mars::smurf::SMURFLoader::loadFile (this=this@entry=0x5555556de3c0, filename="mesh_orientation_tester.urdf", tmpPath="/tmp/mars/14166/", robotname="", args=args@entry=0x0,
do_not_create=do_not_create@entry=false) at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/smurf_loader/src/SMURFLoader.cpp:625
#11 0x00007ffff1c108e5 in mars::smurf::SMURFLoader::loadFile (this=this@entry=0x5555556de3c0, filename="mesh_orientation_tester.urdf", tmpPath="/tmp/mars/14166/", robotname="")
at /usr/include/c++/9/bits/basic_string.h:940
#12 0x00007ffff224fc69 in mars::sim::Simulator::loadScene_internal (this=0x55555580dca0, filename=..., wasrunning=<optimized out>, robotname=...) at /usr/include/c++/9/bits/basic_string.h:267
#13 0x00007ffff22506ae in mars::sim::Simulator::loadScene (this=this@entry=0x55555580dca0, filename=..., wasrunning=wasrunning@entry=false, robotname="", threadsave=threadsave@entry=false,
blocking=blocking@entry=false) at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/sim/src/core/Simulator.cpp:648
#14 0x00007ffff224e243 in mars::sim::Simulator::runSimulation (this=0x55555580dca0, startThread=<optimized out>) at /usr/include/c++/9/ext/aligned_buffer.h:72
#15 0x00007ffff7fba95d in mars::app::MARS::start (this=0x555555578f10, argc=<optimized out>, argv=0x7fffffff0ee8, startThread=<optimized out>, handleLibraryLoading=<optimized out>)
at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/app/src/MARS.cpp:314
#16 0x0000555555556422 in main (argc=<optimized out>, argv=0x7fffffff0ee8) at ${AUTOPROJ_CURRENT_ROOT}/simulation/mars/app/src/main.cpp:83
GAZEBO
For Gazebo I had to adapt the URDF a little, but those changes doesn't affect the behaviour of mesh interpretation:
- giving absoulte pathes for the meshes
- adding an inertial to the link
Regarding the loading of meshes Gazebo beaves exactly as expected. In the images the Origin-Frame of Gazebo is pointing as follows: X is pointing away from the viewer into the screen plane, Y is pointing to the left and Z is pointing upwards. The greyish stuff in front is the shadow of the test mesh.
I suggest for MARS adding the orientation info how the obj-meshes should be parsed in SMURF.