Skip to content

Commit

Permalink
Light: update calls to use sdf::Errors parameters (#1154)
Browse files Browse the repository at this point in the history
* updating Element calls to use Errors

Signed-off-by: Marco A. Gutierrez <[email protected]>

* Light: adding error parameter to function calls

Signed-off-by: Marco A. Gutierrez <[email protected]>

* Adding ToElement errors test

Signed-off-by: Marco A. Gutierrez <[email protected]>

---------

Signed-off-by: Marco A. Gutierrez <[email protected]>
  • Loading branch information
Marco A. Gutierrez authored Mar 28, 2023
1 parent cde899a commit 16457d5
Show file tree
Hide file tree
Showing 3 changed files with 139 additions and 47 deletions.
8 changes: 8 additions & 0 deletions include/sdf/Light.hh
Original file line number Diff line number Diff line change
Expand Up @@ -291,6 +291,14 @@ namespace sdf
/// \return SDF element pointer with updated light values.
public: sdf::ElementPtr ToElement() const;

/// \brief Create and return an SDF element filled with data from this
/// light object.
/// Note that parameter passing functionality is not captured with this
/// function.
/// \param[out] _errors Vector of errors.
/// \return SDF element pointer with updated light values.
public: sdf::ElementPtr ToElement(sdf::Errors &_errors) const;

/// \brief Allow Link::SetPoseRelativeToGraph or World::Load to call
/// SetXmlParentName and SetPoseRelativeToGraph,
/// but Link::SetPoseRelativeToGraph is a private function, so we need
Expand Down
109 changes: 62 additions & 47 deletions src/Light.cc
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ Errors Light::Load(ElementPtr _sdf)
return errors;
}

std::string typeString = _sdf->Get<std::string>("type",
std::string typeString = _sdf->Get<std::string>(errors, "type",
std::string("point")).first;
if (typeString == "point")
this->dataPtr->type = LightType::POINT;
Expand Down Expand Up @@ -148,52 +148,52 @@ Errors Light::Load(ElementPtr _sdf)
// Load the pose. Ignore the return value since the light pose is optional.
loadPose(_sdf, this->dataPtr->pose, this->dataPtr->poseRelativeTo);

this->dataPtr->isLightOn = _sdf->Get<bool>("light_on",
this->dataPtr->isLightOn = _sdf->Get<bool>(errors, "light_on",
this->dataPtr->isLightOn).first;

this->dataPtr->visualize = _sdf->Get<bool>("visualize",
this->dataPtr->visualize = _sdf->Get<bool>(errors, "visualize",
this->dataPtr->visualize).first;

this->dataPtr->castShadows = _sdf->Get<bool>("cast_shadows",
this->dataPtr->castShadows = _sdf->Get<bool>(errors, "cast_shadows",
this->dataPtr->castShadows).first;

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

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

this->dataPtr->specular = _sdf->Get<gz::math::Color>("specular",
this->dataPtr->specular = _sdf->Get<gz::math::Color>(errors, "specular",
this->dataPtr->specular).first;

sdf::ElementPtr attenuationElem = _sdf->GetElement("attenuation");
sdf::ElementPtr attenuationElem = _sdf->GetElement("attenuation", errors);
if (attenuationElem)
{
std::pair<double, bool> doubleValue = attenuationElem->Get<double>(
"range", this->dataPtr->attenuationRange);
errors, "range", this->dataPtr->attenuationRange);
if (!doubleValue.second)
{
errors.push_back({ErrorCode::ELEMENT_MISSING,
"An <attenuation> requires a <range>."});
}
this->SetAttenuationRange(doubleValue.first);

this->SetLinearAttenuationFactor(attenuationElem->Get<double>("linear",
this->dataPtr->linearAttenuation).first);
this->SetLinearAttenuationFactor(attenuationElem->Get<double>(
errors, "linear", this->dataPtr->linearAttenuation).first);

this->SetConstantAttenuationFactor(attenuationElem->Get<double>("constant",
this->dataPtr->constantAttenuation).first);
this->SetConstantAttenuationFactor(attenuationElem->Get<double>(
errors, "constant", this->dataPtr->constantAttenuation).first);

this->SetQuadraticAttenuationFactor(attenuationElem->Get<double>(
"quadratic", this->dataPtr->quadraticAttenuation).first);
errors, "quadratic", this->dataPtr->quadraticAttenuation).first);
}

// Read the direction
if (this->dataPtr->type == LightType::SPOT ||
this->dataPtr->type == LightType::DIRECTIONAL)
{
std::pair<gz::math::Vector3d, bool> dirPair =
_sdf->Get<>("direction", this->dataPtr->direction);
_sdf->Get<>(errors, "direction", this->dataPtr->direction);

if (!dirPair.second)
{
Expand All @@ -204,12 +204,12 @@ Errors Light::Load(ElementPtr _sdf)
this->dataPtr->direction = dirPair.first;
}

sdf::ElementPtr spotElem = _sdf->GetElement("spot");
sdf::ElementPtr spotElem = _sdf->GetElement("spot", errors);
if (this->dataPtr->type == LightType::SPOT && spotElem)
{
// Check for and set inner_angle
std::pair<double, bool> doubleValue = spotElem->Get<double>(
"inner_angle", this->dataPtr->spotInnerAngle.Radian());
errors, "inner_angle", this->dataPtr->spotInnerAngle.Radian());
if (!doubleValue.second)
{
errors.push_back({ErrorCode::ELEMENT_MISSING,
Expand All @@ -219,7 +219,7 @@ Errors Light::Load(ElementPtr _sdf)

// Check for and set outer_angle
doubleValue = spotElem->Get<double>(
"outer_angle", this->dataPtr->spotOuterAngle.Radian());
errors, "outer_angle", this->dataPtr->spotOuterAngle.Radian());
if (!doubleValue.second)
{
errors.push_back({ErrorCode::ELEMENT_MISSING,
Expand All @@ -228,7 +228,8 @@ Errors Light::Load(ElementPtr _sdf)
this->SetSpotOuterAngle(doubleValue.first);

// Check for and set falloff
doubleValue = spotElem->Get<double>("falloff", this->dataPtr->spotFalloff);
doubleValue = spotElem->Get<double>(
errors, "falloff", this->dataPtr->spotFalloff);
if (!doubleValue.second)
{
errors.push_back({ErrorCode::ELEMENT_MISSING,
Expand Down Expand Up @@ -488,6 +489,15 @@ void Light::SetType(const LightType _type)

/////////////////////////////////////////////////
sdf::ElementPtr Light::ToElement() const
{
sdf::Errors errors;
auto result = this->ToElement(errors);
sdf::throwOrPrintErrors(errors);
return result;
}

/////////////////////////////////////////////////
sdf::ElementPtr Light::ToElement(sdf::Errors &_errors) const
{
sdf::ElementPtr elem(new sdf::Element);
sdf::initFile("light.sdf", elem);
Expand All @@ -507,37 +517,42 @@ sdf::ElementPtr Light::ToElement() const
default:
break;
}
elem->GetAttribute("type")->Set<std::string>(lightTypeStr);
elem->GetAttribute("name")->Set<std::string>(this->Name());
sdf::ElementPtr poseElem = elem->GetElement("pose");
elem->GetAttribute("type")->Set<std::string>(lightTypeStr, _errors);
elem->GetAttribute("name")->Set<std::string>(this->Name(), _errors);
sdf::ElementPtr poseElem = elem->GetElement("pose", _errors);
if (!this->dataPtr->poseRelativeTo.empty())
{
poseElem->GetAttribute("relative_to")->Set<std::string>(
this->dataPtr->poseRelativeTo);
this->dataPtr->poseRelativeTo, _errors);
}
poseElem->Set<gz::math::Pose3d>(this->RawPose());

elem->GetElement("cast_shadows")->Set<bool>(this->CastShadows());
elem->GetElement("intensity")->Set<double>(this->Intensity());
elem->GetElement("direction")->Set<gz::math::Vector3d>(
this->Direction());
elem->GetElement("diffuse")->Set<gz::math::Color>(this->Diffuse());
elem->GetElement("specular")->Set<gz::math::Color>(this->Specular());
sdf::ElementPtr attenuationElem = elem->GetElement("attenuation");
attenuationElem->GetElement("linear")->Set<double>(
this->LinearAttenuationFactor());
attenuationElem->GetElement("constant")->Set<double>(
this->ConstantAttenuationFactor());
attenuationElem->GetElement("quadratic")->Set<double>(
this->QuadraticAttenuationFactor());
attenuationElem->GetElement("range")->Set<double>(
this->AttenuationRange());

sdf::ElementPtr spotElem = elem->GetElement("spot");
spotElem->GetElement("inner_angle")->Set<double>(
this->SpotInnerAngle().Radian());
spotElem->GetElement("outer_angle")->Set<double>(
this->SpotOuterAngle().Radian());
spotElem->GetElement("falloff")->Set<double>(this->SpotFalloff());
poseElem->Set<gz::math::Pose3d>(_errors, this->RawPose());

elem->GetElement("cast_shadows", _errors)->Set<bool>(
_errors, this->CastShadows());
elem->GetElement("intensity", _errors)->Set<double>(
_errors, this->Intensity());
elem->GetElement("direction", _errors)->Set<gz::math::Vector3d>(
_errors, this->Direction());
elem->GetElement("diffuse", _errors)->Set<gz::math::Color>(
_errors, this->Diffuse());
elem->GetElement("specular", _errors)->Set<gz::math::Color>(
_errors, this->Specular());
sdf::ElementPtr attenuationElem = elem->GetElement("attenuation", _errors);
attenuationElem->GetElement("linear", _errors)->Set<double>(
_errors, this->LinearAttenuationFactor());
attenuationElem->GetElement("constant", _errors)->Set<double>(
_errors, this->ConstantAttenuationFactor());
attenuationElem->GetElement("quadratic", _errors)->Set<double>(
_errors, this->QuadraticAttenuationFactor());
attenuationElem->GetElement("range", _errors)->Set<double>(
_errors, this->AttenuationRange());

sdf::ElementPtr spotElem = elem->GetElement("spot", _errors);
spotElem->GetElement("inner_angle", _errors)->Set<double>(
_errors, this->SpotInnerAngle().Radian());
spotElem->GetElement("outer_angle", _errors)->Set<double>(
_errors, this->SpotOuterAngle().Radian());
spotElem->GetElement("falloff", _errors)->Set<double>(
_errors, this->SpotFalloff());
return elem;
}
69 changes: 69 additions & 0 deletions src/Light_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtest/gtest.h>
#include <gz/math/Pose3.hh>
#include "sdf/Light.hh"
#include "test_utils.hh"

/////////////////////////////////////////////////
TEST(DOMLight, DefaultConstruction)
Expand Down Expand Up @@ -400,3 +401,71 @@ TEST(DOMLight, ToElement)
light3.Load(light2Elem);
EXPECT_FALSE(light3.CastShadows());
}

/////////////////////////////////////////////////
TEST(DOMLight, ToElementErrorOutput)
{
std::stringstream buffer;
sdf::testing::RedirectConsoleStream redir(
sdf::Console::Instance()->GetMsgStream(), &buffer);

#ifdef _WIN32
sdf::Console::Instance()->SetQuiet(false);
sdf::testing::ScopeExit revertSetQuiet(
[]
{
sdf::Console::Instance()->SetQuiet(true);
});
#endif

// test calling ToElement on a DOM object constructed without calling Load
sdf::Light light;
light.SetName("test_light_assignment");
light.SetType(sdf::LightType::SPOT);
light.SetRawPose({3, 2, 1, 0, GZ_PI, 0});
light.SetPoseRelativeTo("ground_plane");
light.SetCastShadows(true);
light.SetDiffuse(gz::math::Color(0.4f, 0.5f, 0.6f, 1.0));
light.SetSpecular(gz::math::Color(0.8f, 0.9f, 0.1f, 1.0));
light.SetAttenuationRange(3.2);
light.SetLinearAttenuationFactor(0.1);
light.SetConstantAttenuationFactor(0.5);
light.SetQuadraticAttenuationFactor(0.01);
light.SetDirection({0.1, 0.2, 1});
light.SetSpotInnerAngle(1.9);
light.SetSpotOuterAngle(3.3);
light.SetSpotFalloff(0.9);
light.SetIntensity(1.7);

sdf::Errors errors;
sdf::ElementPtr lightElem = light.ToElement(errors);
EXPECT_TRUE(errors.empty());
EXPECT_NE(nullptr, lightElem);
EXPECT_EQ(nullptr, light.Element());

// verify values after loading the element back
sdf::Light light2;
errors = light2.Load(lightElem);
EXPECT_TRUE(errors.empty());

EXPECT_NE(nullptr, light2.Element());
EXPECT_EQ("test_light_assignment", light2.Name());
EXPECT_EQ(sdf::LightType::SPOT, light2.Type());
EXPECT_EQ(gz::math::Pose3d(3, 2, 1, 0, GZ_PI, 0), light2.RawPose());
EXPECT_EQ("ground_plane", light2.PoseRelativeTo());
EXPECT_TRUE(light2.CastShadows());
EXPECT_EQ(gz::math::Color(0.4f, 0.5f, 0.6f, 1), light2.Diffuse());
EXPECT_EQ(gz::math::Color(0.8f, 0.9f, 0.1f, 1), light2.Specular());
EXPECT_DOUBLE_EQ(3.2, light2.AttenuationRange());
EXPECT_DOUBLE_EQ(0.1, light2.LinearAttenuationFactor());
EXPECT_DOUBLE_EQ(0.5, light2.ConstantAttenuationFactor());
EXPECT_DOUBLE_EQ(0.01, light2.QuadraticAttenuationFactor());
EXPECT_EQ(gz::math::Vector3d(0.1, 0.2, 1), light2.Direction());
EXPECT_EQ(gz::math::Angle(1.9), light2.SpotInnerAngle());
EXPECT_EQ(gz::math::Angle(3.3), light2.SpotOuterAngle());
EXPECT_DOUBLE_EQ(0.9, light2.SpotFalloff());
EXPECT_DOUBLE_EQ(1.7, light2.Intensity());

// Check nothing has been printed
EXPECT_TRUE(buffer.str().empty()) << buffer.str();
}

0 comments on commit 16457d5

Please sign in to comment.