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

updated loading //material colors #519

Merged
merged 6 commits into from
Mar 23, 2021
Merged
Show file tree
Hide file tree
Changes from 5 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
76 changes: 60 additions & 16 deletions src/Param.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <locale>
#include <sstream>
#include <string>
#include <vector>

#include <locale.h>
#include <math.h>
Expand Down Expand Up @@ -359,6 +360,63 @@ bool ParseUsingStringStream(const std::string &_input, const std::string &_key,
return true;
}

//////////////////////////////////////////////////
/// \brief Helper function for Param::ValueFromString for parsing colors
/// This checks the color components specified in _input are rgb or rgba
/// (expects 3 or 4 values) and each value is between [0,1]. When only 3 values
/// are present (rgb), then alpha is set to 1.
/// \param[in] _input Input string.
/// \param[in] _key Key of the parameter, used for error message.
/// \param[out] _value This will be set with the parsed value.
/// \return True if parsing colors succeeded.
bool ParseColorUsingStringStream(const std::string &_input,
const std::string &_key, ParamPrivate::ParamVariant &_value)
{
StringStreamClassicLocale ss(_input);
std::string token;
std::vector<float> colors;
float c; // r,g,b,a values
bool isValidColor = true;
while (ss >> token)
{
try
{
c = std::stof(token);
colors.push_back(c);
}
catch(const std::exception &/*e*/)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can the caught exception be more specific like the ones in ValueFromString

https://github.com/osrf/sdformat/blob/deb142130c6fb96b24a2e0f35e481e34ac014834/src/Param.cc#L509-L520

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yup! dbf7614

{
sdferr << "Error converting color value [" << token << "] to a float\n";
isValidColor = false;
break;
}

if (c < 0.0f || c > 1.0f)
{
isValidColor = false;
break;
}
}

size_t colorSize = colors.size();
if (isValidColor && colorSize == 3u)
colors.push_back(1.0f);
else if (colorSize != 4u)
isValidColor = false;

if (isValidColor)
{
_value = ignition::math::Color(colors[0], colors[1], colors[2], colors[3]);
}
else
{
sdferr << "The value <" << _key <<
">" << _input << "</" << _key << "> is invalid.\n";
}

return isValidColor;
}

//////////////////////////////////////////////////
bool Param::ValueFromString(const std::string &_value)
{
Expand Down Expand Up @@ -448,22 +506,8 @@ bool Param::ValueFromString(const std::string &_value)
else if (this->dataPtr->typeName == "ignition::math::Color" ||
this->dataPtr->typeName == "color")
{
// The insertion operator (>>) expects 4 values, but the last value (the
// alpha) is optional. We first try to parse assuming the alpha is
// specified. If that fails, we append the default value of alpha to the
// string and try to parse again.
bool result = ParseUsingStringStream<ignition::math::Color>(
tmp, this->dataPtr->key, this->dataPtr->value);

if (!result)
{
ignition::math::Color colortmp;
return ParseUsingStringStream<ignition::math::Color>(
tmp + " " + std::to_string(colortmp.A()), this->dataPtr->key,
this->dataPtr->value);
}
else
return true;
return ParseColorUsingStringStream(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Vector2i" ||
this->dataPtr->typeName == "vector2i")
Expand Down
9 changes: 8 additions & 1 deletion src/Param_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -290,6 +290,13 @@ TEST(Param, InvalidConstructor)
sdf::AssertionInternalError);
}

////////////////////////////////////////////////////
TEST(Param, InvalidColorConstructor)
{
ASSERT_THROW(sdf::Param("key", "color", "8 20 67 23", false, "description"),
sdf::AssertionInternalError);
}

////////////////////////////////////////////////////
TEST(Param, SetDescription)
{
Expand Down Expand Up @@ -392,7 +399,7 @@ TEST(Param, GetAny)
sdf::Param timeParam("key", "time", "8 20", false, "description");
EXPECT_TRUE(timeParam.GetAny(anyValue));

sdf::Param colorParam("key", "color", "8 20 67 23", false, "description");
sdf::Param colorParam("key", "color", "0 0.1 0.2 0.3", false, "description");
EXPECT_TRUE(colorParam.GetAny(anyValue));

sdf::Param vector3Param("key", "vector3", "8.1 20.24 67.7", false,
Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ set(tests
locale_fix.cc
locale_fix_cxx.cc
material_pbr.cc
material.cc
model_dom.cc
model_versions.cc
nested_model.cc
Expand Down
169 changes: 169 additions & 0 deletions test/integration/material.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,169 @@
/*
* Copyright 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <string>
#include <gtest/gtest.h>

#include <ignition/math/Color.hh>

#include "sdf/sdf.hh"
#include "test_config.h"

void ExpectInvalidWithMessage(sdf::Errors &_errors, std::string _compType)
{
for (const auto &e : _errors)
{
if (e.Message().find(_compType) != std::string::npos)
{
EXPECT_EQ(e.Code(), sdf::ErrorCode::ELEMENT_INVALID);
break;
}
}
}

//////////////////////////////////////////////////
TEST(Material, InvalidColors)
{
std::string testFile =
sdf::testing::TestFile("sdf", "material_invalid.sdf");

sdf::Root root;
sdf::Errors errors = root.Load(testFile);
std::cout << errors << std::endl;

ASSERT_FALSE(errors.empty());
ExpectInvalidWithMessage(errors, "ambient");

// since the above test will break at //ambient, it doesn't test the other
// invalid cases. Below tests these other invalid cases

// less than 3 values
std::string testSDF = R"(
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="model">
<link name="link">
<visual name="material">
<material>
<specular>0 0.1</specular>
</material>
</visual>
</link>
</model>
</sdf>)";

errors.clear();
errors = root.LoadSdfString(testSDF);
std::cout << errors << std::endl;

ASSERT_FALSE(errors.empty());
ExpectInvalidWithMessage(errors, "specular");

// negative value
testSDF = R"(
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="model">
<link name="link">
<visual name="material">
<material>
<emissive>0.1 0.2 -1</emissive>
</material>
</visual>
</link>
</model>
</sdf>)";

errors.clear();
errors = root.LoadSdfString(testSDF);
std::cout << errors << std::endl;

ASSERT_FALSE(errors.empty());
ExpectInvalidWithMessage(errors, "emissive");

// more than 4 values
testSDF = R"(
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="model">
<link name="link">
<visual name="material">
<material>
<diffuse>0.1 0.2 0.3 0.4 0.5</diffuse>
</material>
</visual>
</link>
</model>
</sdf>)";

errors.clear();
errors = root.LoadSdfString(testSDF);
std::cout << errors << std::endl;

ASSERT_FALSE(errors.empty());
ExpectInvalidWithMessage(errors, "diffuse");

// invalid string value
testSDF = R"(
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="model">
<link name="link">
<visual name="material">
<material>
<ambient>0.1 0.2 test</ambient>
</material>
</visual>
</link>
</model>
</sdf>)";

errors.clear();
errors = root.LoadSdfString(testSDF);
std::cout << errors << std::endl;

ASSERT_FALSE(errors.empty());
ExpectInvalidWithMessage(errors, "ambient");
}

//////////////////////////////////////////////////
TEST(Material, ValidColors)
{
std::string testFile =
sdf::testing::TestFile("sdf", "material_valid.sdf");

sdf::Root root;
sdf::Errors errors = root.Load(testFile);
std::cout << errors << std::endl;

ASSERT_TRUE(errors.empty());

sdf::ElementPtr elem = root.Element()->GetElement("model")
->GetElement("link")
->GetElement("visual")
->GetElement("material");
ASSERT_NE(elem, nullptr);

EXPECT_EQ(elem->Get<ignition::math::Color>("diffuse"),
ignition::math::Color(0, 0.1f, 0.2f, 1));
EXPECT_EQ(elem->Get<ignition::math::Color>("specular"),
ignition::math::Color(0, 0.1f, 0.2f, 0.3f));
EXPECT_EQ(elem->Get<ignition::math::Color>("emissive"),
ignition::math::Color(0.12f, 0.23f, 0.34f, 0.56f));
EXPECT_EQ(elem->Get<ignition::math::Color>("ambient"),
ignition::math::Color(0, 0, 0, 1));
}
15 changes: 15 additions & 0 deletions test/sdf/material_invalid.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="model">
<link name="link">
<visual name="material">
<material>
<ambient>1.5 0 0 1</ambient>
<specular>0 0.1</specular>
<emissive>0.1 0.2 -1</emissive>
<diffuse>0.1 0.2 0.3 0.4 0.5</diffuse>
</material>
</visual>
</link>
</model>
</sdf>
14 changes: 14 additions & 0 deletions test/sdf/material_valid.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="model">
<link name="link">
<visual name="material">
<material>
<diffuse>0 0.1 0.2</diffuse>
<specular>0 0.1 0.2 0.3</specular>
<emissive>0.12 0.23 0.34 0.56</emissive>
</material>
</visual>
</link>
</model>
</sdf>