Skip to content

Commit

Permalink
Collada world exporter now exporting lights (#912)
Browse files Browse the repository at this point in the history
Signed-off-by: ddengster <[email protected]>
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
ddengster and chapulina authored Sep 9, 2021
1 parent f388d6e commit 59ff853
Show file tree
Hide file tree
Showing 4 changed files with 249 additions and 3 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR})
#--------------------------------------
# Find ignition-common
# Always use the profiler component to get the headers, regardless of status.
ign_find_package(ignition-common4
ign_find_package(ignition-common4 VERSION 4.2
COMPONENTS
profiler
events
Expand Down
52 changes: 50 additions & 2 deletions src/systems/collada_world_exporter/ColladaWorldExporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <ignition/plugin/Register.hh>

#include <ignition/gazebo/components/Geometry.hh>
#include <ignition/gazebo/components/Light.hh>
#include <ignition/gazebo/components/Link.hh>
#include <ignition/gazebo/components/Material.hh>
#include <ignition/gazebo/components/Model.hh>
Expand All @@ -33,9 +34,10 @@
#include <ignition/gazebo/EntityComponentManager.hh>
#include <ignition/gazebo/Util.hh>

#include <sdf/Visual.hh>
#include <sdf/Light.hh>
#include <sdf/Mesh.hh>
#include <sdf/Model.hh>
#include <sdf/Visual.hh>

#include <ignition/common/Material.hh>
#include <ignition/common/MeshManager.hh>
Expand Down Expand Up @@ -244,9 +246,55 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
return true;
});

std::vector<common::ColladaLight> lights;
_ecm.Each<components::Light,
components::Name>(
[&](const Entity &/*_entity*/,
const components::Light *_light,
const components::Name *_name)->bool
{
std::string name = _name->Data();
const auto& sdfLight = _light->Data();

common::ColladaLight p;
p.name = name;
if (sdfLight.Type() == sdf::LightType::POINT)
{
p.type = "point";
}
else if (sdfLight.Type() == sdf::LightType::SPOT)
{
p.type = "spot";
}
else if (sdfLight.Type() == sdf::LightType::DIRECTIONAL)
{
p.type = "directional";
}
else
{
p.type = "invalid";
}

p.position = sdfLight.RawPose().Pos();
p.direction = sdfLight.RawPose().Rot().RotateVector(sdfLight.Direction());
p.diffuse = sdfLight.Diffuse();

p.constantAttenuation = sdfLight.ConstantAttenuationFactor();
p.linearAttenuation = sdfLight.LinearAttenuationFactor();
p.quadraticAttenuation = sdfLight.QuadraticAttenuationFactor();

// Falloff angle is treated as the outer angle in blender
// https://community.khronos.org/t/spotlight-properties/7111/7
p.falloffAngleDeg = sdfLight.SpotOuterAngle().Degree();
p.falloffExponent = sdfLight.SpotFalloff();

lights.push_back(p);
return true;
});

common::ColladaExporter exporter;
exporter.Export(&worldMesh, "./" + worldMesh.Name(), true,
subMeshMatrix);
subMeshMatrix, lights);
ignmsg << "The world has been exported into the "
<< "./" + worldMesh.Name() << " directory." << std::endl;
this->exported = true;
Expand Down
21 changes: 21 additions & 0 deletions test/integration/collada_world_exporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,27 @@ TEST_F(ColladaWorldExporterFixture, ExportWorldMadeFromObj)
common::removeAll(outputPath);
}

TEST_F(ColladaWorldExporterFixture, ExportWorldWithLights)
{
this->LoadWorld(common::joinPaths("test", "worlds",
"collada_world_exporter_lights.sdf"));

// Cleanup
common::removeAll("./collada_world_exporter_lights_test");

// The export directory shouldn't exist.
EXPECT_FALSE(common::exists("./collada_world_exporter_lights_test"));

// Run one iteration which should export the world.
server->Run(true, 1, false);

// The export directory should now exist.
EXPECT_TRUE(common::exists("./collada_world_exporter_lights_test"));

// Cleanup
common::removeAll("./collada_world_exporter_lights_test");
}

/////////////////////////////////////////////////
/// Main
int main(int _argc, char **_argv)
Expand Down
177 changes: 177 additions & 0 deletions test/worlds/collada_world_exporter_lights.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,177 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="collada_world_exporter_lights_test">

<plugin
filename="ignition-gazebo-collada-world-exporter-system"
name="ignition::gazebo::systems::ColladaWorldExporter">
</plugin>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="box">
<pose>0 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="cylinder">
<pose>0 -1.5 0.5 0 0 0</pose>
<link name="cylinder_link">
<inertial>
<inertia>
<ixx>2</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2</iyy>
<iyz>0</iyz>
<izz>2</izz>
</inertia>
<mass>2.0</mass>
</inertial>
<collision name="cylinder_collision">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
</collision>

<visual name="cylinder_visual">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="sphere">
<pose>0 1.5 0.5 0 0 0</pose>
<link name="sphere_link">
<inertial>
<inertia>
<ixx>3</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>3</iyy>
<iyz>0</iyz>
<izz>3</izz>
</inertia>
<mass>3.0</mass>
</inertial>
<collision name="sphere_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>

<visual name="sphere_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
</link>
</model>

<light type="point" name="point_light">
<pose>0 2 2 0 0 0</pose>
<diffuse>1 0 0 1</diffuse>
<specular>.1 .1 .1 1</specular>
<attenuation>
<range>20</range>
<linear>0.2</linear>
<constant>0.8</constant>
<quadratic>0.01</quadratic>
</attenuation>
<cast_shadows>false</cast_shadows>
</light>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 5 0 45 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

</world>
</sdf>

0 comments on commit 59ff853

Please sign in to comment.