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

Added lights intensity field #484

Merged
merged 3 commits into from
Feb 5, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
8 changes: 8 additions & 0 deletions include/sdf/Light.hh
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,14 @@ namespace sdf
/// \param[in] _cast True to indicate that the light casts shadows.
public: void SetCastShadows(const bool _cast);

/// \brief Get the light intensity
/// \return The light intensity
public: double Intensity() const;

/// \brief Set the light intensity
/// \param[in] _intensity New light intensity
public: void SetIntensity(const double _intensity);

/// \brief Get the diffuse color. The diffuse color is
/// specified by a set of three numbers representing red/green/blue,
/// each in the range of [0,1].
Expand Down
4 changes: 4 additions & 0 deletions sdf/1.8/light.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,10 @@
<description>When true, the light will cast shadows.</description>
</element>

<element name="intensity" type="double" default="1" required="0">
<description>Scale factor to set the relative power of a light.</description>
</element>

<include filename="pose.sdf" required="0"/>

<element name="diffuse" type="color" default="1 1 1 1" required="0">
Expand Down
19 changes: 19 additions & 0 deletions src/Light.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,9 @@ class sdf::LightPrivate
/// \brief True if the light should cast shadows.
public: bool castShadows = false;

/// \brief Spot light falloff.
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
public: double intensity = 1.0;

/// \brief The attenation range.
public: double attenuationRange = 10.0;

Expand Down Expand Up @@ -140,6 +143,7 @@ void Light::CopyFrom(const Light &_light)
this->dataPtr->spotInnerAngle = _light.dataPtr->spotInnerAngle;
this->dataPtr->spotOuterAngle = _light.dataPtr->spotOuterAngle;
this->dataPtr->spotFalloff = _light.dataPtr->spotFalloff;
this->dataPtr->intensity = _light.dataPtr->intensity;
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -195,6 +199,9 @@ Errors Light::Load(ElementPtr _sdf)
this->dataPtr->castShadows = _sdf->Get<bool>("cast_shadows",
this->dataPtr->castShadows).first;

this->dataPtr->intensity = _sdf->Get<double>("intensity",
this->dataPtr->intensity).first;

this->dataPtr->diffuse = _sdf->Get<ignition::math::Color>("diffuse",
this->dataPtr->diffuse).first;

Expand Down Expand Up @@ -340,6 +347,18 @@ sdf::ElementPtr Light::Element() const
return this->dataPtr->sdf;
}

/////////////////////////////////////////////////
double Light::Intensity() const
{
return this->dataPtr->intensity;
}

/////////////////////////////////////////////////
void Light::SetIntensity(const double _intensity)
{
this->dataPtr->intensity = _intensity;
}

/////////////////////////////////////////////////
bool Light::CastShadows() const
{
Expand Down
12 changes: 12 additions & 0 deletions src/Light_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,10 @@ TEST(DOMLight, DefaultConstruction)
EXPECT_DOUBLE_EQ(0.0, light.SpotFalloff());
light.SetSpotFalloff(4.3);
EXPECT_DOUBLE_EQ(4.3, light.SpotFalloff());

EXPECT_DOUBLE_EQ(1.0, light.Intensity());
light.SetIntensity(0.3);
EXPECT_DOUBLE_EQ(0.3, light.Intensity());
}

/////////////////////////////////////////////////
Expand All @@ -119,6 +123,7 @@ TEST(DOMLight, CopyConstructor)
light.SetSpotInnerAngle(1.9);
light.SetSpotOuterAngle(3.3);
light.SetSpotFalloff(0.9);
light.SetIntensity(1.7);

sdf::Light light2(light);
EXPECT_EQ("test_copy_light", light2.Name());
Expand All @@ -136,6 +141,7 @@ TEST(DOMLight, CopyConstructor)
EXPECT_EQ(ignition::math::Angle(1.9), light2.SpotInnerAngle());
EXPECT_EQ(ignition::math::Angle(3.3), light2.SpotOuterAngle());
EXPECT_DOUBLE_EQ(0.9, light2.SpotFalloff());
EXPECT_DOUBLE_EQ(1.7, light2.Intensity());
}

/////////////////////////////////////////////////
Expand All @@ -157,6 +163,7 @@ TEST(DOMLight, CopyAssignmentOperator)
light.SetSpotInnerAngle(1.9);
light.SetSpotOuterAngle(3.3);
light.SetSpotFalloff(0.9);
light.SetIntensity(1.7);

sdf::Light light2;
light2 = light;
Expand All @@ -175,6 +182,7 @@ TEST(DOMLight, CopyAssignmentOperator)
EXPECT_EQ(ignition::math::Angle(1.9), light2.SpotInnerAngle());
EXPECT_EQ(ignition::math::Angle(3.3), light2.SpotOuterAngle());
EXPECT_DOUBLE_EQ(0.9, light2.SpotFalloff());
EXPECT_DOUBLE_EQ(1.7, light2.Intensity());
}

/////////////////////////////////////////////////
Expand All @@ -196,6 +204,7 @@ TEST(DOMLight, MoveConstructor)
light.SetSpotInnerAngle(1.9);
light.SetSpotOuterAngle(3.3);
light.SetSpotFalloff(0.9);
light.SetIntensity(1.7);

sdf::Light light2(std::move(light));
EXPECT_EQ("test_light_assignment", light2.Name());
Expand All @@ -213,6 +222,7 @@ TEST(DOMLight, MoveConstructor)
EXPECT_EQ(ignition::math::Angle(1.9), light2.SpotInnerAngle());
EXPECT_EQ(ignition::math::Angle(3.3), light2.SpotOuterAngle());
EXPECT_DOUBLE_EQ(0.9, light2.SpotFalloff());
EXPECT_DOUBLE_EQ(1.7, light2.Intensity());
}

/////////////////////////////////////////////////
Expand All @@ -234,6 +244,7 @@ TEST(DOMLight, MoveAssignment)
light.SetSpotInnerAngle(1.9);
light.SetSpotOuterAngle(3.3);
light.SetSpotFalloff(0.9);
light.SetIntensity(1.7);

sdf::Light light2;
light2 = std::move(light);
Expand All @@ -252,6 +263,7 @@ TEST(DOMLight, MoveAssignment)
EXPECT_EQ(ignition::math::Angle(1.9), light2.SpotInnerAngle());
EXPECT_EQ(ignition::math::Angle(3.3), light2.SpotOuterAngle());
EXPECT_DOUBLE_EQ(0.9, light2.SpotFalloff());
EXPECT_DOUBLE_EQ(1.7, light2.Intensity());
}

/////////////////////////////////////////////////
Expand Down
3 changes: 3 additions & 0 deletions test/integration/light_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ TEST(DOMWorld, LoadLights)
EXPECT_DOUBLE_EQ(1.0, pointLight->LinearAttenuationFactor());
EXPECT_DOUBLE_EQ(0.0, pointLight->ConstantAttenuationFactor());
EXPECT_DOUBLE_EQ(20.2, pointLight->QuadraticAttenuationFactor());
EXPECT_DOUBLE_EQ(1.0, pointLight->Intensity());

const sdf::Light *spotLight = world->LightByIndex(1);
ASSERT_NE(nullptr, spotLight);
Expand All @@ -68,6 +69,7 @@ TEST(DOMWorld, LoadLights)
EXPECT_DOUBLE_EQ(0.1, spotLight->SpotInnerAngle().Radian());
EXPECT_DOUBLE_EQ(0.5, spotLight->SpotOuterAngle().Radian());
EXPECT_DOUBLE_EQ(2.2, spotLight->SpotFalloff());
EXPECT_DOUBLE_EQ(1.0, spotLight->Intensity());

const sdf::Light *dirLight = world->LightByIndex(2);
ASSERT_NE(nullptr, dirLight);
Expand All @@ -84,6 +86,7 @@ TEST(DOMWorld, LoadLights)
EXPECT_DOUBLE_EQ(0.0, dirLight->LinearAttenuationFactor());
EXPECT_DOUBLE_EQ(1.0, dirLight->ConstantAttenuationFactor());
EXPECT_DOUBLE_EQ(0.0, dirLight->QuadraticAttenuationFactor());
EXPECT_DOUBLE_EQ(1.8, dirLight->Intensity());

const sdf::Model *model = world->ModelByIndex(0);
ASSERT_NE(nullptr, model);
Expand Down
1 change: 1 addition & 0 deletions test/sdf/world_complete.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@
<constant>2.0</constant>
<quadratic>-100.2</quadratic>
</attenuation>
<intensity>1.8</intensity>
</light>

<frame name="frame1" attached_to="world">
Expand Down