Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

This fix for cases where VERTEX and NROMAL share same polylist <p> , see https://github.com/osrf/gazebo/issues/2682#issue-602951524 #2811

Merged
merged 3 commits into from
Aug 11, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion gazebo/common/ColladaLoader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1595,8 +1595,12 @@ void ColladaLoader::LoadPolylist(TiXmlElement *_polylistXml,
polylistInputXml = polylistInputXml->NextSiblingElement("input");
}

std::set<int> totalInputs;
for (const auto &input : inputs)
inputSize += input.second.size();
{
totalInputs.insert(input.second.begin(), input.second.end());
}
inputSize += totalInputs.size();

// read vcount
// break poly into triangles
Expand Down
30 changes: 30 additions & 0 deletions test/integration/collada_visualization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,5 +50,35 @@ void ColladaVisualization::MultipleTextureCoordinates()
delete mainWindow;
}

/////////////////////////////////////////////////
void ColladaVisualization::AssimpVersion4MultipleInputWithSameOffset()
{
this->resMaxPercentChange = 5.0;
this->shareMaxPercentChange = 2.0;

this->Load("worlds/multiple_input_with_same_offset_test.world",
false, false, false);

gazebo::gui::MainWindow *mainWindow = new gazebo::gui::MainWindow();
QVERIFY(mainWindow != NULL);

// Create the main window.
mainWindow->Load();
mainWindow->Init();
mainWindow->show();

// Get the user camera and scene
gazebo::rendering::UserCameraPtr cam = gazebo::gui::get_active_camera();
QVERIFY(cam != NULL);

this->ProcessEventsAndDraw(mainWindow);

// There should be two triangles.
QCOMPARE(cam->TriangleCount(), 24u);

mainWindow->close();
delete mainWindow;
}

// Generate a main function for the test
QTEST_MAIN(ColladaVisualization)
4 changes: 4 additions & 0 deletions test/integration/collada_visualization.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,10 @@ class ColladaVisualization : public QTestFixture
/// \brief Test loading a collada mesh that has multiple texture
/// coordinates
private slots: void MultipleTextureCoordinates();

/// \brief Test loading a collada mesh that has multiple inputs
/// with same offset, see https://github.com/osrf/gazebo/issues/2682
void AssimpVersion4MultipleInputWithSameOffset();
};

#endif
89 changes: 89 additions & 0 deletions test/media/models/box-assimp-3.dae
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
<?xml version="1.0"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Assimp</author>
<authoring_tool>Assimp Collada Exporter</authoring_tool>
</contributor>
<created>2020-08-02T13:13:20</created>
<modified>2020-08-02T13:13:20</modified>
<unit name="meter" meter="1" />
<up_axis>Y_UP</up_axis>
</asset>
<library_effects>
<effect id="m0DefaultMaterial-fx" name="m0DefaultMaterial">
<profile_COMMON>
<technique sid="common">
<phong>
<ambient>
<color sid="ambient">0.05 0.05 0.05 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.6 0.6 0.6 1</color>
</diffuse>
<specular>
<color sid="specular">0.6 0.6 0.6 1</color>
</specular>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="m0DefaultMaterial" name="m0DefaultMaterial">
<instance_effect url="#m0DefaultMaterial-fx"/>
</material>
</library_materials>
<library_geometries>
<geometry id="meshId0" name="meshId0_name" >
<mesh>
<source id="meshId0-positions" name="meshId0-positions">
<float_array id="meshId0-positions-array" count="108"> -0.5 -0.5 -0.5 -0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 -0.5 -0.5 -0.5 -0.5 -0.5 0.5 -0.5 0.5 0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 -0.5 0.5 0.5 -0.5 0.5 -0.5 0.5 0.5 0.5 0.5 0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 0.5 0.5 0.5 0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 0.5 0.5 -0.5 0.5 0.5 0.5 0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 -0.5 -0.5 -0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 -0.5 -0.5 -0.5 -0.5 0.5 </float_array>
<technique_common>
<accessor count="36" offset="0" source="#meshId0-positions-array" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="meshId0-normals" name="meshId0-normals">
<float_array id="meshId0-normals-array" count="108"> 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 </float_array>
<technique_common>
<accessor count="36" offset="0" source="#meshId0-normals-array" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="meshId0-vertices">
<input semantic="POSITION" source="#meshId0-positions" />
<input semantic="NORMAL" source="#meshId0-normals" />
</vertices>
<polylist count="12" material="theresonlyone">
<input offset="0" semantic="VERTEX" source="#meshId0-vertices" />
<vcount>3 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 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 </p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="AssimpScene" name="AssimpScene">
<matrix>1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#meshId0">
<bind_material>
<technique_common>
<instance_material symbol="theresonlyone" target="#m0DefaultMaterial" />
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene" />
</scene>
</COLLADA>
92 changes: 92 additions & 0 deletions test/media/models/box-assimp-4.dae
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Assimp</author>
<authoring_tool>Assimp Exporter</authoring_tool>
</contributor>
<created>2020-08-02T13:05:04</created>
<modified>2020-08-02T13:05:04</modified>
<unit name="meter" meter="1" />
<up_axis>Y_UP</up_axis>
</asset>
<library_effects>
<effect id="DefaultMaterial-fx" name="DefaultMaterial">
<profile_COMMON>
<technique sid="standard">
<phong>
<ambient>
<color sid="ambient">1 1 1 1</color>
</ambient>
<diffuse>
<color sid="diffuse">1 1 1 1</color>
</diffuse>
<specular>
<color sid="specular">1 1 1 1</color>
</specular>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="DefaultMaterial" name="DefaultMaterial">
<instance_effect url="#DefaultMaterial-fx"/>
</material>
</library_materials>
<library_geometries>
<geometry id="meshId0" name="meshId0_name" >
<mesh>
<source id="meshId0-positions" name="meshId0-positions">
<float_array id="meshId0-positions-array" count="108"> -0.5 -0.5 -0.5 -0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 -0.5 -0.5 -0.5 -0.5 -0.5 0.5 -0.5 0.5 0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 -0.5 0.5 0.5 -0.5 0.5 -0.5 0.5 0.5 0.5 0.5 0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 0.5 0.5 0.5 0.5 0.5 0.5 -0.5 0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 0.5 0.5 -0.5 0.5 0.5 0.5 0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 -0.5 -0.5 -0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 0.5 0.5 -0.5 0.5 -0.5 -0.5 0.5 -0.5 -0.5 -0.5 -0.5 -0.5 -0.5 0.5 </float_array>
<technique_common>
<accessor count="36" offset="0" source="#meshId0-positions-array" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<source id="meshId0-normals" name="meshId0-normals">
<float_array id="meshId0-normals-array" count="108"> 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 </float_array>
<technique_common>
<accessor count="36" offset="0" source="#meshId0-normals-array" stride="3">
<param name="X" type="float" />
<param name="Y" type="float" />
<param name="Z" type="float" />
</accessor>
</technique_common>
</source>
<vertices id="meshId0-vertices">
<input semantic="POSITION" source="#meshId0-positions" />
</vertices>
<polylist count="12" 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 3 </vcount>
<p>0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 </p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers>
</library_controllers>
<library_visual_scenes>
<visual_scene id="" name="">
<node id="AssimpScene" name="AssimpScene" type="NODE">
<matrix sid="matrix">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#meshId0">
<bind_material>
<technique_common>
<instance_material symbol="defaultMaterial" target="#DefaultMaterial">
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#" />
</scene>
</COLLADA>
45 changes: 45 additions & 0 deletions test/worlds/multiple_input_with_same_offset_test.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">

<include>
<uri>model://sun</uri>
</include>

<!-- <scene> -->
<!-- <background>0 0 0 1</background> -->
<!-- <ambient>1 1 1 1</ambient> -->
<!-- <grid>false</grid> -->
<!-- <origin_visual>false</origin_visual> -->
<!-- </scene> -->

<gui>
<camera name="user">
<pose>-15 0 15 0 0.785398 0</pose>
</camera>
</gui>

<model name="model">
<static>true</static>
<link name="link">
<visual name="visual-assimp-3">
<pose>0 5 0.5 0 0 0</pose>
<geometry>
<mesh>
<uri>file://media/models/box-assimp-3.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="visual-assimp-4">
<pose>0 -5 0.5 0 0 0</pose>
<geometry>
<mesh>
<uri>file://media/models/box-assimp-4.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>

</world>
</sdf>