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

Make parsing of values syntactically more strict with bad values generating an error #244

Merged
merged 8 commits into from
Jun 4, 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
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@

### libsdformat 10.0.0 (202X-XX-XX)

1. Make parsing of values syntactically more strict with bad values generating an error
* [Pull request 244](https://github.com/osrf/sdformat/pull/244)

1. Don't install deprecated parser_urdf.hh header file, fix cmake warning about newline file, fix cmake warning about newlines.
* [Pull request 276](https://github.com/osrf/sdformat/pull/276)

Expand Down
6 changes: 6 additions & 0 deletions include/sdf/Types.hh
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,12 @@ namespace sdf
SDFORMAT_VISIBLE
std::string trim(const char *_in);

/// \brief Trim leading and trailing whitespace from a string.
/// \param[in] _in The string to trim.
/// \return A string containing the trimmed value.
SDFORMAT_VISIBLE
std::string trim(const std::string &_in);

/// \brief check if two values are equal, within a tolerance
/// \param[in] _a the first value
/// \param[in] _b the second value
Expand Down
101 changes: 59 additions & 42 deletions src/Param.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
*/

#include <algorithm>
#include <cctype>
#include <cstdint>
#include <locale>
#include <sstream>
Expand Down Expand Up @@ -271,16 +272,39 @@ std::string Param::GetDefaultAsString() const
return ss.str();
}

//////////////////////////////////////////////////
/// \brief Helper function for Param::ValueFromString
/// \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 succeeded.
template <typename T>
bool ParseUsingStringStream(const std::string &_input, const std::string &_key,
ParamPrivate::ParamVariant &_value)
{
StringStreamClassicLocale ss(_input);
T _val;
ss >> _val;
if (ss.fail())
{
sdferr << "Unknown error. Unable to set value [" << _input << " ] for key["
<< _key << "]\n";
return false;
}
_value = _val;
return true;
}

//////////////////////////////////////////////////
bool Param::ValueFromString(const std::string &_value)
{
// Under some circumstances, latin locales (es_ES or pt_BR) will return a
// comma for decimal position instead of a dot, making the conversion
// to fail. See bug #60 for more information. Force to use always C
setlocale(LC_NUMERIC, "C");

std::string tmp(_value);
std::string lowerTmp = lowercase(_value);
std::string trimmed = sdf::trim(_value);
std::string tmp(trimmed);
std::string lowerTmp = lowercase(trimmed);

// "true" and "false" doesn't work properly
if (lowerTmp == "true")
Expand Down Expand Up @@ -335,11 +359,8 @@ bool Param::ValueFromString(const std::string &_value)
}
else if (this->dataPtr->typeName == "uint64_t")
{
StringStreamClassicLocale ss(tmp);
std::uint64_t u64tmp;

ss >> u64tmp;
this->dataPtr->value = u64tmp;
return ParseUsingStringStream<std::uint64_t>(tmp, this->dataPtr->key,
this->dataPtr->value);
}
else if (this->dataPtr->typeName == "unsigned int")
{
Expand All @@ -357,66 +378,62 @@ bool Param::ValueFromString(const std::string &_value)
else if (this->dataPtr->typeName == "sdf::Time" ||
this->dataPtr->typeName == "time")
{
StringStreamClassicLocale ss(tmp);
sdf::Time timetmp;

ss >> timetmp;
this->dataPtr->value = timetmp;
return ParseUsingStringStream<sdf::Time>(tmp, this->dataPtr->key,
this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Color" ||
this->dataPtr->typeName == "color")
{
StringStreamClassicLocale ss(tmp);
ignition::math::Color colortmp;
// 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);

ss >> colortmp;
this->dataPtr->value = colortmp;
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;
}
else if (this->dataPtr->typeName == "ignition::math::Vector2i" ||
this->dataPtr->typeName == "vector2i")
{
StringStreamClassicLocale ss(tmp);
ignition::math::Vector2i vectmp;

ss >> vectmp;
this->dataPtr->value = vectmp;
return ParseUsingStringStream<ignition::math::Vector2i>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Vector2d" ||
this->dataPtr->typeName == "vector2d")
{
StringStreamClassicLocale ss(tmp);
ignition::math::Vector2d vectmp;

ss >> vectmp;
this->dataPtr->value = vectmp;
return ParseUsingStringStream<ignition::math::Vector2d>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Vector3d" ||
this->dataPtr->typeName == "vector3")
{
StringStreamClassicLocale ss(tmp);
ignition::math::Vector3d vectmp;

ss >> vectmp;
this->dataPtr->value = vectmp;
return ParseUsingStringStream<ignition::math::Vector3d>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Pose3d" ||
this->dataPtr->typeName == "pose" ||
this->dataPtr->typeName == "Pose")
{
StringStreamClassicLocale ss(tmp);
ignition::math::Pose3d posetmp;

ss >> posetmp;
this->dataPtr->value = posetmp;
if (!tmp.empty())
{
return ParseUsingStringStream<ignition::math::Pose3d>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
Copy link
Member

Choose a reason for hiding this comment

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

I think the changes to this block are not needed because Param::SetFromString already calls sdf::trim to remove whitespace and then sets a default value if the trimmed string is empty. I've added tests to confirm this in 9daad39 of branch scpeters/stricter_parsing_10 after reverting the changes to this block in 8f6120c

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Sounds good. I see that ValueFromString is also called form the constructor without sdf::trim, but that should be okay because it's using the default string from the spec description.
https://github.com/osrf/sdformat/blob/b80e070dbed613e972acfb81e66b24a248eefd6c/src/Param.cc#L70

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

I just tried it and it looks like UNIT_Utils_TEST fails with that change.

Copy link
Member

Choose a reason for hiding this comment

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

ok, it sounds like this change is a good idea. Perhaps we could generalize it so it applies to types other than Pose?

Copy link
Member

Choose a reason for hiding this comment

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

I think we discussed this in our last meeting, and this was the last change we expected to make?

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

I added an overload for sdf::trim that takes a std::string in fdecf77, and used that to trim input values in 32b3d84

}
else if (this->dataPtr->typeName == "ignition::math::Quaterniond" ||
this->dataPtr->typeName == "quaternion")
{
StringStreamClassicLocale ss(tmp);
ignition::math::Quaterniond quattmp;

ss >> quattmp;
this->dataPtr->value = quattmp;
return ParseUsingStringStream<ignition::math::Quaterniond>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else
{
Expand Down
12 changes: 8 additions & 4 deletions src/Types.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,17 +53,21 @@ std::vector<std::string> split(const std::string &_str,
//////////////////////////////////////////////////
std::string trim(const char *_in)
{
std::string str(_in);
return sdf::trim(std::string(_in));
}

const size_t strBegin = str.find_first_not_of(" \t");
//////////////////////////////////////////////////
std::string trim(const std::string &_in)
{
const size_t strBegin = _in.find_first_not_of(" \t");
if (strBegin == std::string::npos)
{
return "";
}

const size_t strRange = str.find_last_not_of(" \t") - strBegin + 1;
const size_t strRange = _in.find_last_not_of(" \t") - strBegin + 1;

return str.substr(strBegin, strRange);
return _in.substr(strBegin, strRange);
}

/////////////////////////////////////////////////
Expand Down
61 changes: 61 additions & 0 deletions src/parser_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -472,6 +472,67 @@ TEST(Parser, NameUniqueness)
}
}

/////////////////////////////////////////////////
/// Check that _a contains _b
static bool contains(const std::string &_a, const std::string &_b)
{
return _a.find(_b) != std::string::npos;
}

/////////////////////////////////////////////////
TEST(Parser, SyntaxErrorInValues)
{
std::string pathBase = PROJECT_SOURCE_PATH;
pathBase += "/test/sdf";

// Capture sdferr output
std::stringstream buffer;
auto old = std::cerr.rdbuf(buffer.rdbuf());

#ifdef _WIN32
sdf::Console::Instance()->SetQuiet(false);
#endif

{
std::string path = pathBase +"/bad_syntax_pose.sdf";
sdf::SDFPtr sdf(new sdf::SDF());
sdf::init(sdf);

sdf::readFile(path, sdf);
EXPECT_PRED2(contains, buffer.str(),
"Unable to set value [bad 0 0 0 0 0 ] for key[pose]");
}
{
// clear the contents of the buffer
buffer.str("");
std::string path = pathBase +"/bad_syntax_double.sdf";
sdf::SDFPtr sdf(new sdf::SDF());
sdf::init(sdf);

sdf::readFile(path, sdf);
EXPECT_PRED2(contains, buffer.str(),
"Unable to set value [bad ] for key[linear]");
}
{
// clear the contents of the buffer
buffer.str("");
std::string path = pathBase +"/bad_syntax_vector.sdf";
sdf::SDFPtr sdf(new sdf::SDF());
sdf::init(sdf);

sdf::readFile(path, sdf);
EXPECT_PRED2(contains, buffer.str(),
"Unable to set value [0 1 bad ] for key[gravity]");
}

// Revert cerr rdbug so as to not interfere with other tests
std::cerr.rdbuf(old);
#ifdef _WIN32
sdf::Console::Instance()->SetQuiet(true);
#endif
}

/////////////////////////////////////////////////
/////////////////////////////////////////////////
/// Main
int main(int argc, char **argv)
Expand Down
13 changes: 13 additions & 0 deletions test/sdf/bad_syntax_double.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<model name="robot1">
<link name="link">
<velocity_decay>
<linear>bad</linear>
</velocity_decay>
</link>
</model>
</world>
</sdf>

10 changes: 10 additions & 0 deletions test/sdf/bad_syntax_pose.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<model name="robot1">
<pose>bad 0 0 0 0 0</pose>
<link name="link"/>
</model>
</world>
</sdf>

7 changes: 7 additions & 0 deletions test/sdf/bad_syntax_vector.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<gravity>0 1 bad</gravity>
</world>
</sdf>

2 changes: 1 addition & 1 deletion test/sdf/box_bad_test.world
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<sdf version="1.6">
<world name="default">
<model name="box">
<pose>0 0.5 0.0 0.0 0.0</pose>
<pose>0 0.5 0.0 0.0 0.0 0.0</pose>
<link>
<inertial>
<mass>0.05</mass>
Expand Down