From 4ea168cc0f0f4d44dcd157fdaae8f16f037b1797 Mon Sep 17 00:00:00 2001 From: "Marco A. Gutierrez" Date: Thu, 5 May 2022 12:53:39 +0000 Subject: [PATCH 1/2] adding vector of errors to param functions Signed-off-by: Marco A. Gutierrez --- include/sdf/Error.hh | 8 + include/sdf/Param.hh | 252 ++++++++++++- src/Param.cc | 582 +++++++++++++++++++++++-------- test/integration/CMakeLists.txt | 1 + test/integration/error_output.cc | 132 +++++++ 5 files changed, 810 insertions(+), 165 deletions(-) create mode 100644 test/integration/error_output.cc diff --git a/include/sdf/Error.hh b/include/sdf/Error.hh index 104f88051..b76949b8f 100644 --- a/include/sdf/Error.hh +++ b/include/sdf/Error.hh @@ -147,6 +147,14 @@ namespace sdf /// \brief Merge include is unspported for the type of entity being /// included, or the custom parser does not support merge includes. MERGE_INCLUDE_UNSUPPORTED, + + /// \brief Generic error type for parameters (values of SDFormat elements + /// or attributes). + PARAMETER_ERROR, + + /// \brief The specified parameter (values of SDFormat elements + /// or attributes) type is unknown. + UNKNOWN_PARAMETER_TYPE, }; class SDFORMAT_VISIBLE Error diff --git a/include/sdf/Param.hh b/include/sdf/Param.hh index 513c8d29d..a50893d93 100644 --- a/include/sdf/Param.hh +++ b/include/sdf/Param.hh @@ -136,6 +136,19 @@ namespace sdf const std::string &_default, bool _required, const std::string &_description = ""); + /// \brief Constructor. + /// \param[in] _key Key for the parameter. + /// \param[in] _typeName String name for the value type (double, + /// int,...). + /// \param[in] _default Default value. + /// \param[in] _required True if the parameter is required to be set. + /// \param[out] _errors Vector of errors. + /// \param[in] _description Description of the parameter. + public: Param(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + sdf::Errors &_errors, + const std::string &_description = ""); + /// \brief Constructor with min and max values. /// \param[in] _key Key for the parameter. /// \param[in] _typeName String name for the value type (double, @@ -151,6 +164,22 @@ namespace sdf const std::string &_minValue, const std::string &_maxValue, const std::string &_description = ""); + /// \brief Constructor with min and max values. + /// \param[in] _key Key for the parameter. + /// \param[in] _typeName String name for the value type (double, + /// int,...). + /// \param[in] _default Default value. + /// \param[in] _required True if the parameter is required to be set. + /// \param[in] _minValue Minimum allowed value for the parameter. + /// \param[in] _maxValue Maximum allowed value for the parameter. + /// \param[out] _errors Vector of errors. + /// \param[in] _description Description of the parameter. + public: Param(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + const std::string &_minValue, const std::string &_maxValue, + sdf::Errors &_errors, + const std::string &_description = ""); + /// \brief Copy constructor /// Note that the updateFunc member does not get copied /// \param[in] _param Param to copy @@ -180,21 +209,47 @@ namespace sdf public: std::string GetAsString( const PrintConfig &_config = PrintConfig()) const; + /// \brief Get the value as a string. + /// \param[out] _errors Vector of errors. + /// \param[in] _config Configuration for conversion to string. + /// \return String containing the value of the parameter. + public: std::string GetAsString( + sdf::Errors &_errors, + const PrintConfig &_config = PrintConfig()) const; + + /// \brief Get the default value as a string. + /// \param[in] _config Configuration for conversion to string. + /// \return String containing the default value of the parameter. + public: std::string GetDefaultAsString( + const PrintConfig &_config = PrintConfig()) const; + /// \brief Get the default value as a string. + /// \param[out] _errors Vector of errors. /// \param[in] _config Configuration for conversion to string. /// \return String containing the default value of the parameter. public: std::string GetDefaultAsString( + sdf::Errors &_errors, + const PrintConfig &_config = PrintConfig()) const; + + /// \brief Get the minimum allowed value as a string. + /// \param[in] _config Configuration for conversion to string. + /// \return Returns a string containing the minimum allowed value of the + /// parameter if the minimum value is specified in the SDFormat description + /// of the parameter. nullopt otherwise. + public: std::optional GetMinValueAsString( const PrintConfig &_config = PrintConfig()) const; - /// \brief Get the minimum allowed value as a string + /// \brief Get the minimum allowed value as a string. + /// \param[out] _errors Vector of errors. /// \param[in] _config Configuration for conversion to string. /// \return Returns a string containing the minimum allowed value of the /// parameter if the minimum value is specified in the SDFormat description /// of the parameter. nullopt otherwise. public: std::optional GetMinValueAsString( + sdf::Errors &_errors, const PrintConfig &_config = PrintConfig()) const; - /// \brief Get the maximum allowed value as a string + /// \brief Get the maximum allowed value as a string. /// \param[in] _config Configuration for conversion to string. /// \return Returns a string containing the maximum allowed value of the /// parameter if the maximum value is specified in the SDFormat description @@ -202,6 +257,16 @@ namespace sdf public: std::optional GetMaxValueAsString( const PrintConfig &_config = PrintConfig()) const; + /// \brief Get the maximum allowed value as a string. + /// \param[in] _config Configuration for conversion to string. + /// \param[out] _errors Vector of errors. + /// \return Returns a string containing the maximum allowed value of the + /// parameter if the maximum value is specified in the SDFormat description + /// of the parameter. nullopt otherwise. + public: std::optional GetMaxValueAsString( + sdf::Errors &_errors, + const PrintConfig &_config = PrintConfig()) const; + /// \brief Set the parameter value from a string. /// \param[in] _value New value for the parameter in string form. /// \param[in] _ignoreParentAttributes Whether to ignore parent element @@ -210,10 +275,26 @@ namespace sdf public: bool SetFromString(const std::string &_value, bool _ignoreParentAttributes); + /// \brief Set the parameter value from a string. + /// \param[in] _value New value for the parameter in string form. + /// \param[in] _ignoreParentAttributes Whether to ignore parent element + /// \param[out] _errors Vector of errors. + /// attributes when parsing value from string as well as subsequent + /// reparses. + public: bool SetFromString(const std::string &_value, + bool _ignoreParentAttributes, + sdf::Errors &_errors); + /// \brief Set the parameter value from a string. /// \param[in] _value New value for the parameter in string form. public: bool SetFromString(const std::string &_value); + /// \brief Set the parameter value from a string. + /// \param[in] _value New value for the parameter in string form. + /// \param[out] _errors Vector of errors. + public: bool SetFromString(const std::string &_value, + sdf::Errors &_errors); + /// \brief Get the parent Element of this Param. /// \return Pointer to this Param's parent Element, nullptr if there is no /// parent Element. @@ -226,6 +307,15 @@ namespace sdf /// successfully. public: bool SetParentElement(ElementPtr _parentElement); + /// \brief Set the parent Element of this Param. + /// \param[in] _parentElement Pointer to new parent Element. A nullptr can + /// provided to remove the current parent Element. + /// \param[out] _errors Vector of errors. + /// \return True if the parent Element was set and the value was reparsed + /// successfully. + public: bool SetParentElement(ElementPtr _parentElement, + sdf::Errors &_errors); + /// \brief Reset the parameter to the default value. public: void Reset(); @@ -242,6 +332,20 @@ namespace sdf /// \sa bool Set(const T &_value) public: bool Reparse(); + /// \brief Reparse the parameter value. This should be called after the + /// parent element's attributes have been modified, in the event that the + /// value was set using SetFromString or posesses a default value, and that + /// the final parsed value is dependent on the attributes of the parent + /// element. For example, the rotation component of a pose element can + /// be parsed as degrees or radians, depending on the attribute @degrees + /// of the parent element. If however the value was explicitly set using the + /// Set function, reparsing would not change the value. + /// \param[out] _errors Vector of errors. + /// \return True if the parameter value has been reparsed successfully. + /// \sa bool SetFromString(const std::string &_value) + /// \sa bool Set(const T &_value) + public: bool Reparse(sdf::Errors &_errors); + /// \brief Get the key value. /// \return The key. public: const std::string &GetKey() const; @@ -284,6 +388,11 @@ namespace sdf /// \sa Param::SetUpdateFunc public: void Update(); + /// \brief Set the parameter's value using the updateFunc. + /// \param[out] _errors Vector of errors. + /// \sa Param::SetUpdateFunc + public: void Update(sdf::Errors &_errors); + /// \brief Set the parameter's value. /// /// The passed in value value must have an input and output stream operator. @@ -292,11 +401,27 @@ namespace sdf public: template bool Set(const T &_value); + /// \brief Set the parameter's value. + /// + /// The passed in value value must have an input and output stream operator. + /// \param[in] _value The value to set the parameter to. + /// \param[out] _errors Vector of errors. + /// \return True if the value was successfully set. + public: template + bool Set(const T &_value, + sdf::Errors &_errors); + /// \brief Get the value of the parameter as a std::any. /// \param[out] _anyVal The std::any object to set. /// \return True if successfully fetched _anyVal, false otherwise. public: bool GetAny(std::any &_anyVal) const; + /// \brief Get the value of the parameter as a std::any. + /// \param[out] _anyVal The std::any object to set. + /// \param[out] _errors Vector of errors. + /// \return True if successfully fetched _anyVal, false otherwise. + public: bool GetAny(std::any &_anyVal, sdf::Errors &_errors) const; + /// \brief Get the value of the parameter. /// \param[out] _value The value of the parameter. /// \return True if parameter was successfully cast to the value type @@ -304,6 +429,15 @@ namespace sdf public: template bool Get(T &_value) const; + /// \brief Get the value of the parameter. + /// \param[out] _value The value of the parameter. + /// \param[out] _errors Vector of errors. + /// \return True if parameter was successfully cast to the value type + /// passed in. + public: template + bool Get(T &_value, + sdf::Errors &_errors) const; + /// \brief Get the default value of the parameter. /// \param[out] _value The default value of the parameter. /// \return True if parameter was successfully cast to the value type @@ -311,6 +445,15 @@ namespace sdf public: template bool GetDefault(T &_value) const; + /// \brief Get the default value of the parameter. + /// \param[out] _value The default value of the parameter. + /// \param[out] _errors Vector of errors. + /// \return True if parameter was successfully cast to the value type + /// passed in. + public: template + bool GetDefault(T &_value, + sdf::Errors &_errors) const; + /// \brief Set the description of the parameter. /// \param[in] _desc New description for the parameter. public: void SetDescription(const std::string &_desc); @@ -323,6 +466,11 @@ namespace sdf /// \return True if the value is valid public: bool ValidateValue() const; + /// \brief Validate the value against minimum and maximum allowed values + /// \param[out] _errors Vector of errors. + /// \return True if the value is valid + public: bool ValidateValue(sdf::Errors &_errors) const; + /// \brief Ostream operator. Outputs the parameter's value. /// \param[in] _out Output stream. /// \param[in] _p The parameter to output. @@ -401,15 +549,46 @@ namespace sdf /// \brief This parameter's maximum allowed value public: std::optional maxValue; + /// \brief Initializer function to help Param constructors. + /// \param[in] _key Key for the parameter. + /// \param[in] _typeName String name for the value type (double, + /// int,...). + /// \param[in] _default Default value. + /// \param[in] _required True if the parameter is required to be set. + /// \param[out] _errors Vector of errors. + /// \param[in] _description Description of the parameter. + public: void Init(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + sdf::Errors &_errors, + const std::string &_description); + + /// \brief Initializer function to help Param constructors. + /// \param[in] _key Key for the parameter. + /// \param[in] _typeName String name for the value type (double, + /// int,...). + /// \param[in] _default Default value. + /// \param[in] _required True if the parameter is required to be set. + /// \param[in] _minValue Minimum allowed value for the parameter. + /// \param[in] _maxValue Maximum allowed value for the parameter. + /// \param[out] _errors Vector of errors. + /// \param[in] _description Description of the parameter. + public: void Init(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + const std::string &_minValue, const std::string &_maxValue, + sdf::Errors &_errors, + const std::string &_description); + /// \brief Method used to set the Param from a passed-in string /// \param[in] _typeName The data type of the value to set /// \param[in] _valueStr The value as a string /// \param[out] _valueToSet The value to set + /// \param[out] _errors Vector of errors. /// \return True if the value was successfully set, false otherwise public: bool SDFORMAT_VISIBLE ValueFromStringImpl( const std::string &_typeName, const std::string &_valueStr, - ParamVariant &_valueToSet) const; + ParamVariant &_valueToSet, + sdf::Errors &_errors) const; /// \brief Method used to get the string representation from a ParamVariant, /// or the string that was used to set it. @@ -417,12 +596,14 @@ namespace sdf /// \param[in] _typeName The data type of the value /// \param[in] _value The value /// \param[out] _valueStr The output string. + /// \param[out] _errors Vector of errors. /// \return True if the string was successfully retrieved, false otherwise. public: bool StringFromValueImpl( const PrintConfig &_config, const std::string &_typeName, const ParamVariant &_value, - std::string &_valueStr) const; + std::string &_valueStr, + sdf::Errors &_errors) const; /// \brief Data type to string mapping /// \return The type as a string, empty string if unknown type @@ -481,19 +662,31 @@ namespace sdf /////////////////////////////////////////////// template bool Param::Set(const T &_value) + { + sdf::Errors errors; + bool result = this->Set(_value, errors); + if (!errors.empty()) + sdferr << errors; + return result; + } + + /////////////////////////////////////////////// + template + bool Param::Set(const T &_value, sdf::Errors &_errors) { try { std::stringstream ss; ss << _value; - return this->SetFromString(ss.str(), true); + return this->SetFromString(ss.str(), true, _errors); } catch(...) { - sdferr << "Unable to set parameter[" - << this->dataPtr->key << "]." - << "Type used must have a stream input and output operator," - << "which allows proper functioning of Param.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to set parameter[" + + this->dataPtr->key + "]." + + "Type used must have a stream input and output operator," + + "which allows proper functioning of Param."}); return false; } } @@ -501,6 +694,17 @@ namespace sdf /////////////////////////////////////////////// template bool Param::Get(T &_value) const + { + sdf::Errors errors; + bool result = this->Get(_value, errors); + if (!errors.empty()) + sdferr << errors; + return result; + } + + /////////////////////////////////////////////// + template + bool Param::Get(T &_value, sdf::Errors &_errors) const { T *value = std::get_if(&this->dataPtr->value); if (value) @@ -512,13 +716,15 @@ namespace sdf std::string typeStr = this->dataPtr->TypeToString(); if (typeStr.empty()) { - sdferr << "Unknown parameter type[" << typeid(T).name() << "]\n"; + _errors.push_back({ErrorCode::UNKNOWN_PARAMETER_TYPE, + "Unknown parameter type[" + std::string(typeid(T).name()) + "]"}); return false; } - std::string valueStr = this->GetAsString(); + std::string valueStr = this->GetAsString(_errors); ParamPrivate::ParamVariant pv; - bool success = this->dataPtr->ValueFromStringImpl(typeStr, valueStr, pv); + bool success = this->dataPtr->ValueFromStringImpl( + typeStr, valueStr, pv, _errors); if (success) { @@ -550,6 +756,17 @@ namespace sdf /////////////////////////////////////////////// template bool Param::GetDefault(T &_value) const + { + sdf::Errors errors; + bool result = this>GetDefault(_value, errors); + if (!errors.empty()) + sdferr << errors; + return result; + } + + /////////////////////////////////////////////// + template + bool Param::GetDefault(T &_value, sdf::Errors &_errors) const { std::stringstream ss; @@ -560,11 +777,12 @@ namespace sdf } catch(...) { - sdferr << "Unable to convert parameter[" - << this->dataPtr->key << "] " - << "whose type is[" - << this->dataPtr->typeName << "], to " - << "type[" << typeid(T).name() << "]\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to convert parameter[" + + this->dataPtr->key + "] " + + "whose type is[" + + this->dataPtr->typeName + "], to " + + "type[" + typeid(T).name() + "]"}); return false; } diff --git a/src/Param.cc b/src/Param.cc index 15b2ee3f1..b42841b7c 100644 --- a/src/Param.cc +++ b/src/Param.cc @@ -65,22 +65,30 @@ Param::Param(const std::string &_key, const std::string &_typeName, const std::string &_description) : dataPtr(new ParamPrivate) { - this->dataPtr->key = _key; - this->dataPtr->required = _required; - this->dataPtr->typeName = _typeName; - this->dataPtr->description = _description; - this->dataPtr->set = false; - this->dataPtr->ignoreParentAttributes = false; - this->dataPtr->defaultStrValue = _default; + sdf::Errors errors; + this->dataPtr->Init(_key, _typeName, _default, _required, + errors, _description); - SDF_ASSERT( - this->dataPtr->ValueFromStringImpl( - this->dataPtr->typeName, - _default, - this->dataPtr->defaultValue), - "Invalid parameter"); - this->dataPtr->value = this->dataPtr->defaultValue; - this->dataPtr->strValue = std::nullopt; + if(!errors.empty()) + { + for (unsigned int i = 0; i < errors.size() - 1; ++i) + { + sdferr << errors[i].Message() << "\n"; + } + + SDF_ASSERT(false, errors.back().Message()); + } +} + +////////////////////////////////////////////////// +Param::Param(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + sdf::Errors &_errors, + const std::string &_description) + : dataPtr(new ParamPrivate) +{ + this->dataPtr->Init(_key, _typeName, _default, _required, + _errors, _description); } ////////////////////////////////////////////////// @@ -88,31 +96,35 @@ Param::Param(const std::string &_key, const std::string &_typeName, const std::string &_default, bool _required, const std::string &_minValue, const std::string &_maxValue, const std::string &_description) - : Param(_key, _typeName, _default, _required, _description) + : dataPtr(new ParamPrivate) { - if (!_minValue.empty()) - { - SDF_ASSERT( - this->dataPtr->ValueFromStringImpl( - this->dataPtr->typeName, - _minValue, - this->dataPtr->minValue.emplace()), - std::string("Invalid [min] parameter in SDFormat description of [") + - _key + "]"); - } + sdf::Errors errors; + this->dataPtr->Init(_key, _typeName, _default, _required, _minValue, + _maxValue, errors, _description); - if (!_maxValue.empty()) + if(!errors.empty()) { - SDF_ASSERT( - this->dataPtr->ValueFromStringImpl( - this->dataPtr->typeName, - _maxValue, - this->dataPtr->maxValue.emplace()), - std::string("Invalid [max] parameter in SDFormat description of [") + - _key + "]"); + for (unsigned int i = 0; i < errors.size() - 1; ++i) + { + sdferr << errors[i].Message() << "\n"; + } + + SDF_ASSERT(false, errors.back().Message()); } } +////////////////////////////////////////////////// +Param::Param(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + const std::string &_minValue, const std::string &_maxValue, + sdf::Errors &_errors, + const std::string &_description) + : dataPtr(new ParamPrivate) +{ + this->dataPtr->Init(_key, _typeName, _default, _required, _minValue, + _maxValue, _errors, _description); +} + ////////////////////////////////////////////////// Param::Param(const Param &_param) : dataPtr(std::make_unique(*_param.dataPtr)) @@ -139,12 +151,27 @@ Param &Param::operator=(const Param &_param) ////////////////////////////////////////////////// bool Param::GetAny(std::any &_anyVal) const +{ + sdf::Errors errors; + this->GetAny(_anyVal, errors); + if(!errors.empty()) + { + sdferr << errors; + return false; + } + return true; +} + +////////////////////////////////////////////////// +bool Param::GetAny(std::any &_anyVal, sdf::Errors &_errors) const { if (this->IsType()) { int ret = 0; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [int]"}); return false; } _anyVal = ret; @@ -152,8 +179,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { uint64_t ret = 0; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [uint64_t]"}); return false; } _anyVal = ret; @@ -161,8 +190,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { double ret = 0; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [double]"}); return false; } _anyVal = ret; @@ -170,8 +201,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { float ret = 0; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [float]"}); return false; } _anyVal = ret; @@ -179,8 +212,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { bool ret = false; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [bool]"}); return false; } _anyVal = ret; @@ -188,8 +223,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { std::string ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [std::string]"}); return false; } _anyVal = ret; @@ -197,8 +234,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { unsigned int ret = 0; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [unsigned int]"}); return false; } _anyVal = ret; @@ -206,8 +245,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { char ret = 0; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [char]"}); return false; } _anyVal = ret; @@ -215,8 +256,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { sdf::Time ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [char]"}); return false; } _anyVal = ret; @@ -224,8 +267,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { ignition::math::Color ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [ignition::math::Color]"}); return false; } _anyVal = ret; @@ -233,8 +278,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { ignition::math::Vector3d ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [ignition::math::Vector3d]"}); return false; } _anyVal = ret; @@ -242,8 +289,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { ignition::math::Vector2i ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [ignition::math::Vector2i]"}); return false; } _anyVal = ret; @@ -251,8 +300,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { ignition::math::Vector2d ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [ignition::math::Vector2d]"}); return false; } _anyVal = ret; @@ -260,8 +311,10 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { ignition::math::Pose3d ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [ignition::math::Pose3d]"}); return false; } _anyVal = ret; @@ -269,15 +322,18 @@ bool Param::GetAny(std::any &_anyVal) const else if (this->IsType()) { ignition::math::Quaterniond ret; - if (!this->Get(ret)) + if (!this->Get(ret, _errors)) { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Could not get a parameter of type [ignition::math::Quaterniond]"}); return false; } _anyVal = ret; } else { - sdferr << "Type of parameter not known: [" << this->GetTypeName() << "]\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Type of parameter not known: [" + this->GetTypeName() + "]"}); return false; } return true; @@ -285,6 +341,15 @@ bool Param::GetAny(std::any &_anyVal) const ////////////////////////////////////////////////// void Param::Update() +{ + sdf::Errors errors; + this->Update(errors); + if (!errors.empty()) + sdferr << errors; +} + +////////////////////////////////////////////////// +void Param::Update(sdf::Errors &_errors) { if (this->dataPtr->updateFunc) { @@ -299,43 +364,75 @@ void Param::Update() } catch(...) { - sdferr << "Unable to set value using Update for key[" - << this->dataPtr->key << "]\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to set value using Update for key[" + + this->dataPtr->key + "]"}); } } + else + { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "[updateFunc] is not set."}); + } } ////////////////////////////////////////////////// std::string Param::GetAsString(const PrintConfig &_config) const +{ + sdf::Errors errors; + std::string result = GetAsString(errors, _config); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +std::string Param::GetAsString(sdf::Errors &_errors, + const PrintConfig &_config) const { std::string valueStr; if (this->GetSet() && this->dataPtr->StringFromValueImpl(_config, this->dataPtr->typeName, this->dataPtr->value, - valueStr)) + valueStr, + _errors)) { return valueStr; } - return this->GetDefaultAsString(_config); + return this->GetDefaultAsString(_errors, _config); } ////////////////////////////////////////////////// std::string Param::GetDefaultAsString(const PrintConfig &_config) const +{ + sdf::Errors errors; + std::string result = this->GetDefaultAsString(errors, _config); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +std::string Param::GetDefaultAsString(sdf::Errors &_errors, + const PrintConfig &_config) const { std::string defaultStr; if (this->dataPtr->StringFromValueImpl( _config, this->dataPtr->typeName, this->dataPtr->defaultValue, - defaultStr)) + defaultStr, + _errors)) { return defaultStr; } - sdferr << "Unable to get string from default value, " - << "using ParamStreamer instead.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to get string from default value, " + "using ParamStreamer instead."}); + StringStreamClassicLocale ss; ss << ParamStreamer{ this->dataPtr->defaultValue, _config.OutPrecision() }; return ss.str(); @@ -344,6 +441,18 @@ std::string Param::GetDefaultAsString(const PrintConfig &_config) const ////////////////////////////////////////////////// std::optional Param::GetMinValueAsString( const PrintConfig &_config) const +{ + sdf::Errors errors; + auto result = GetMinValueAsString(errors, _config); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +std::optional Param::GetMinValueAsString( + sdf::Errors &_errors, + const PrintConfig &_config) const { if (this->dataPtr->minValue.has_value()) { @@ -351,9 +460,11 @@ std::optional Param::GetMinValueAsString( if (!this->dataPtr->StringFromValueImpl(_config, this->dataPtr->typeName, this->dataPtr->minValue.value(), - valueStr)) + valueStr, + _errors)) { - sdferr << "Unable to get min value as string.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to get min value as string."}); return std::nullopt; } @@ -365,6 +476,18 @@ std::optional Param::GetMinValueAsString( ////////////////////////////////////////////////// std::optional Param::GetMaxValueAsString( const PrintConfig &_config) const +{ + sdf::Errors errors; + auto result = GetMaxValueAsString(errors, _config); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +std::optional Param::GetMaxValueAsString( + sdf::Errors &_errors, + const PrintConfig &_config) const { if (this->dataPtr->maxValue.has_value()) { @@ -372,9 +495,11 @@ std::optional Param::GetMaxValueAsString( if (!this->dataPtr->StringFromValueImpl(_config, this->dataPtr->typeName, this->dataPtr->maxValue.value(), - valueStr)) + valueStr, + _errors)) { - sdferr << "Unable to get max value as string.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to get max value as string."}); return std::nullopt; } @@ -388,18 +513,21 @@ std::optional Param::GetMaxValueAsString( /// \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. +/// \param[out] _errors Vector of errors. /// \return True if parsing succeeded. template bool ParseUsingStringStream(const std::string &_input, const std::string &_key, - ParamPrivate::ParamVariant &_value) + ParamPrivate::ParamVariant &_value, + sdf::Errors &_errors) { StringStreamClassicLocale ss(_input); T _val; ss >> _val; if (ss.fail()) { - sdferr << "Unknown error. Unable to set value [" << _input << " ] for key[" - << _key << "]\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unknown error. Unable to set value [" + _input + " ] for key[" + + _key + "]"}); return false; } _value = _val; @@ -414,9 +542,11 @@ bool ParseUsingStringStream(const std::string &_input, const std::string &_key, /// \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. +/// \param[out] _errors Vector of errors. /// \return True if parsing colors succeeded. bool ParseColorUsingStringStream(const std::string &_input, - const std::string &_key, ParamPrivate::ParamVariant &_value) + const std::string &_key, ParamPrivate::ParamVariant &_value, + sdf::Errors &_errors) { StringStreamClassicLocale ss(_input); std::string token; @@ -433,16 +563,18 @@ bool ParseColorUsingStringStream(const std::string &_input, // Catch invalid argument exception from std::stof catch(std::invalid_argument &) { - sdferr << "Invalid argument. Unable to set value ["<< token - << "] for key [" << _key << "].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid argument. Unable to set value [" + token + + "] for key [" + _key + "]."}); isValidColor = false; break; } // Catch out of range exception from std::stof catch(std::out_of_range &) { - sdferr << "Out of range. Unable to set value [" << token - << "] for key [" << _key << "].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Out of range. Unable to set value [" + token + + "] for key [" + _key + "]."}); isValidColor = false; break; } @@ -466,8 +598,8 @@ bool ParseColorUsingStringStream(const std::string &_input, } else { - sdferr << "The value <" << _key << - ">" << _input << " is invalid.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "The value <" + _key + ">" + _input + " is invalid."}); } return isValidColor; @@ -482,10 +614,12 @@ bool ParseColorUsingStringStream(const std::string &_input, /// \param[in] _key Key of the parameter, used for error message. /// \param[in] _attributes Attributes associated to this pose. /// \param[out] _value This will be set with the parsed value. +/// \param[out] _errors Vector of errors. /// \return True if parsing pose succeeded. bool ParsePoseUsingStringStream(const std::string &_input, const std::string &_key, const Param_V &_attributes, - ParamPrivate::ParamVariant &_value) + ParamPrivate::ParamVariant &_value, + sdf::Errors &_errors) { const bool defaultParseAsDegrees = false; bool parseAsDegrees = defaultParseAsDegrees; @@ -502,16 +636,17 @@ bool ParsePoseUsingStringStream(const std::string &_input, if (key == "degrees") { - if (!p->Get(parseAsDegrees)) + if (!p->Get(parseAsDegrees, _errors)) { - sdferr << "Invalid boolean value found for attribute " - "//pose[@degrees].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid boolean value found for attribute " + "//pose[@degrees]."}); return false; } } else if (key == "rotation_format") { - rotationFormat = p->GetAsString(); + rotationFormat = p->GetAsString(_errors); if (rotationFormat == "euler_rpy") { @@ -523,9 +658,10 @@ bool ParsePoseUsingStringStream(const std::string &_input, } else { - sdferr << "Undefined attribute //pose[@rotation_format='" - << rotationFormat << "'], only 'euler_rpy' and 'quat_xyzw'" - << " is supported.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Undefined attribute //pose[@rotation_format='" + + rotationFormat + "'], only 'euler_rpy' and 'quat_xyzw'" + + " is supported."}); return false; } } @@ -533,8 +669,9 @@ bool ParsePoseUsingStringStream(const std::string &_input, if (rotationFormat == "quat_xyzw" && parseAsDegrees) { - sdferr << "The attribute //pose[@degrees='true'] does not apply when " - << "parsing quaternions, //pose[@rotation_format='quat_xyzw'].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "The attribute //pose[@degrees='true'] does not apply when " + "parsing quaternions, //pose[@rotation_format='quat_xyzw']."}); return false; } @@ -559,32 +696,36 @@ bool ParsePoseUsingStringStream(const std::string &_input, // Catch invalid argument exception from std::stod catch(std::invalid_argument &) { - sdferr << "Invalid argument. Unable to set value ["<< _input - << "] for key [" << _key << "].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid argument. Unable to set value [" + _input + + "] for key [" + _key + "]."}); isValidPose = false; break; } // Catch out of range exception from std::stod catch(std::out_of_range &) { - sdferr << "Out of range. Unable to set value [" << token - << "] for key [" << _key << "].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Out of range. Unable to set value [" + token + + "] for key [" + _key + "]."}); isValidPose = false; break; } if (!std::isfinite(v)) { - sdferr << "Pose values must be finite.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Pose values must be finite."}); isValidPose = false; break; } if (valueIndex >= desiredSize) { - sdferr << "The value for //pose[@rotation_format='" << rotationFormat - << "'] must have " << desiredSize - << " values, but more than that were found in '" << _input << "'.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "The value for //pose[@rotation_format='" + rotationFormat + + "'] must have " + std::to_string(desiredSize) + + " values, but more than that were found in '" + _input + "'."}); isValidPose = false; break; } @@ -597,9 +738,11 @@ bool ParsePoseUsingStringStream(const std::string &_input, if (valueIndex != desiredSize) { - sdferr << "The value for //pose[@rotation_format='" << rotationFormat - << "'] must have " << desiredSize << " values, but " << valueIndex - << " were found instead in '" << _input << "'.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "The value for //pose[@rotation_format='" + rotationFormat + + "'] must have " + std::to_string(desiredSize) + " values, but " + + std::to_string(valueIndex) + " were found instead in '" + + _input + "'."}); return false; } @@ -625,10 +768,77 @@ bool ParsePoseUsingStringStream(const std::string &_input, return true; } +////////////////////////////////////////////////// +void ParamPrivate::Init(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + sdf::Errors &_errors, + const std::string &_description) +{ + this->key = _key; + this->required = _required; + this->typeName = _typeName; + this->description = _description; + this->set = false; + this->ignoreParentAttributes = false; + this->defaultStrValue = _default; + + if(!(this->ValueFromStringImpl( + this->typeName, + _default, + this->defaultValue, + _errors))) + { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid parameter"}); + return; + } + this->value = this->defaultValue; + this->strValue = std::nullopt; +} + +////////////////////////////////////////////////// +void ParamPrivate::Init(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + const std::string &_minValue, const std::string &_maxValue, + sdf::Errors &_errors, + const std::string &_description) +{ + this->Init(_key, _typeName, _default, _required, _errors, _description); + if (!_minValue.empty()) + { + if (!(this->ValueFromStringImpl( + this->typeName, + _minValue, + this->minValue.emplace(), + _errors))) + { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid [min] parameter in " + "SDFormat description of [" + _key + "]"}); + } + } + + if (!_maxValue.empty()) + { + if(!(this->ValueFromStringImpl( + this->typeName, + _maxValue, + this->maxValue.emplace(), + _errors))) + + { + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid [max] parameter in SDFormat description of [" + + _key + "]"}); + } + } +} + ////////////////////////////////////////////////// bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, const std::string &_valueStr, - ParamVariant &_valueToSet) const + ParamVariant &_valueToSet, + sdf::Errors &_errors) const { // Under some circumstances, latin locales (es_ES or pt_BR) will return a // comma for decimal position instead of a dot, making the conversion @@ -675,7 +885,8 @@ bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, } else { - sdferr << "Invalid boolean value\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid boolean value"}); return false; } } @@ -695,7 +906,7 @@ bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, else if (_typeName == "uint64_t") { return ParseUsingStringStream(tmp, this->key, - _valueToSet); + _valueToSet, _errors); } else if (_typeName == "unsigned int") { @@ -714,36 +925,36 @@ bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, _typeName == "time") { return ParseUsingStringStream(tmp, this->key, - _valueToSet); + _valueToSet, _errors); } else if (_typeName == "ignition::math::Angle" || _typeName == "angle") { return ParseUsingStringStream( - tmp, this->key, _valueToSet); + tmp, this->key, _valueToSet, _errors); } else if (_typeName == "ignition::math::Color" || _typeName == "color") { - return ParseColorUsingStringStream(tmp, this->key, _valueToSet); + return ParseColorUsingStringStream(tmp, this->key, _valueToSet, _errors); } else if (_typeName == "ignition::math::Vector2i" || _typeName == "vector2i") { return ParseUsingStringStream( - tmp, this->key, _valueToSet); + tmp, this->key, _valueToSet, _errors); } else if (_typeName == "ignition::math::Vector2d" || _typeName == "vector2d") { return ParseUsingStringStream( - tmp, this->key, _valueToSet); + tmp, this->key, _valueToSet, _errors); } else if (_typeName == "ignition::math::Vector3d" || _typeName == "vector3") { return ParseUsingStringStream( - tmp, this->key, _valueToSet); + tmp, this->key, _valueToSet, _errors); } else if (_typeName == "ignition::math::Pose3d" || _typeName == "pose" || @@ -753,37 +964,40 @@ bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, if (!this->ignoreParentAttributes && p) { return ParsePoseUsingStringStream( - tmp, this->key, p->GetAttributes(), _valueToSet); + tmp, this->key, p->GetAttributes(), _valueToSet, _errors); } return ParsePoseUsingStringStream( - tmp, this->key, {}, _valueToSet); + tmp, this->key, {}, _valueToSet, _errors); } else if (_typeName == "ignition::math::Quaterniond" || _typeName == "quaternion") { return ParseUsingStringStream( - tmp, this->key, _valueToSet); + tmp, this->key, _valueToSet, _errors); } else { - sdferr << "Unknown parameter type[" << _typeName << "]\n"; + _errors.push_back({ErrorCode::UNKNOWN_PARAMETER_TYPE, + "Unknown parameter type[" + _typeName + "]"}); return false; } } // Catch invalid argument exception from std::stoi/stoul/stod/stof catch(std::invalid_argument &) { - sdferr << "Invalid argument. Unable to set value [" - << _valueStr << " ] for key[" - << this->key << "].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid argument. Unable to set value [" + + _valueStr + " ] for key[" + + this->key + "]."}); return false; } // Catch out of range exception from std::stoi/stoul/stod/stof catch(std::out_of_range &) { - sdferr << "Out of range. Unable to set value [" - << _valueStr << " ] for key[" - << this->key << "].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Out of range. Unable to set value [" + + _valueStr + " ] for key[" + + this->key + "]."}); return false; } @@ -796,13 +1010,15 @@ bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, /// \param[in] _parentAttributes Parent Element Attributes. /// \param[in] _value The variant value of this pose. /// \param[out] _valueStr The pose as a string. +/// \param[out] _errors Vector of errors. /// \return True if the string was successfully retrieved from the pose, false /// otherwise. ///////////////////////////////////////////////// bool PoseStringFromValue(const PrintConfig &_config, const Param_V &_parentAttributes, const ParamPrivate::ParamVariant &_value, - std::string &_valueStr) + std::string &_valueStr, + sdf::Errors &_errors) { StringStreamClassicLocale ss; @@ -815,7 +1031,8 @@ bool PoseStringFromValue(const PrintConfig &_config, std::get_if(&_value); if (!pose) { - sdferr << "Unable to get pose value from variant.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to get pose value from variant."}); return false; } @@ -841,9 +1058,10 @@ bool PoseStringFromValue(const PrintConfig &_config, if (key == "degrees") { - if (!p->Get(inDegrees)) + if (!p->Get(inDegrees, _errors)) { - sdferr << "Unable to get //pose[@degrees] attribute as bool.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to get //pose[@degrees] attribute as bool."}); return false; } if (p->GetSet()) @@ -853,7 +1071,7 @@ bool PoseStringFromValue(const PrintConfig &_config, } else if (key == "rotation_format") { - rotationFormat = p->GetAsString(); + rotationFormat = p->GetAsString(_errors); if (p->GetSet()) { posRotDelimiter = threeSpacedDelimiter; @@ -901,8 +1119,9 @@ bool PoseStringFromValue(const PrintConfig &_config, // Returning pose string representations based on desired configurations. if (rotationFormat == "quat_xyzw" && inDegrees) { - sdferr << "Invalid pose with //pose[@degrees='true'] and " - << "//pose[@rotation_format='quat_xyzw'].\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Invalid pose with //pose[@degrees='true'] and " + "//pose[@rotation_format='quat_xyzw']."}); return false; } else if (rotationFormat == "quat_xyzw") @@ -968,7 +1187,8 @@ bool ParamPrivate::StringFromValueImpl( const PrintConfig &_config, const std::string &_typeName, const ParamVariant &_value, - std::string &_valueStr) const + std::string &_valueStr, + sdf::Errors &_errors) const { // This will be handled in a type specific manner if (_typeName == "bool") @@ -976,7 +1196,8 @@ bool ParamPrivate::StringFromValueImpl( const bool *val = std::get_if(&_value); if (!val) { - sdferr << "Unable to get bool value from variant.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Unable to get bool value from variant."}); return false; } @@ -991,9 +1212,9 @@ bool ParamPrivate::StringFromValueImpl( if (!this->ignoreParentAttributes && p) { return PoseStringFromValue( - _config, p->GetAttributes(), _value, _valueStr); + _config, p->GetAttributes(), _value, _valueStr, _errors); } - return PoseStringFromValue(_config, {}, _value, _valueStr); + return PoseStringFromValue(_config, {}, _value, _valueStr, _errors); } StringStreamClassicLocale ss; @@ -1005,14 +1226,29 @@ bool ParamPrivate::StringFromValueImpl( ////////////////////////////////////////////////// bool Param::SetFromString(const std::string &_value, bool _ignoreParentAttributes) +{ + sdf::Errors errors; + bool result = this->SetFromString(_value, + _ignoreParentAttributes, + errors); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +bool Param::SetFromString(const std::string &_value, + bool _ignoreParentAttributes, + sdf::Errors &_errors) { this->dataPtr->ignoreParentAttributes = _ignoreParentAttributes; std::string str = sdf::trim(_value.c_str()); if (str.empty() && this->dataPtr->required) { - sdferr << "Empty string used when setting a required parameter. Key[" - << this->GetKey() << "]\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Empty string used when setting a required parameter. Key[" + + this->GetKey() + "]"}); return false; } else if (str.empty()) @@ -1025,14 +1261,15 @@ bool Param::SetFromString(const std::string &_value, auto oldValue = this->dataPtr->value; if (!this->dataPtr->ValueFromStringImpl(this->dataPtr->typeName, str, - this->dataPtr->value)) + this->dataPtr->value, + _errors)) { return false; } this->dataPtr->strValue = str; // Check if the value is permitted - if (!this->ValidateValue()) + if (!this->ValidateValue(_errors)) { this->dataPtr->value = oldValue; return false; @@ -1045,7 +1282,17 @@ bool Param::SetFromString(const std::string &_value, ////////////////////////////////////////////////// bool Param::SetFromString(const std::string &_value) { - return this->SetFromString(_value, false); + sdf::Errors errors; + bool result = this->SetFromString(_value, false, errors); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +bool Param::SetFromString(const std::string &_value, sdf::Errors &_errors) +{ + return this->SetFromString(_value, false, _errors); } ////////////////////////////////////////////////// @@ -1056,11 +1303,21 @@ ElementPtr Param::GetParentElement() const ////////////////////////////////////////////////// bool Param::SetParentElement(ElementPtr _parentElement) +{ + sdf::Errors errors; + bool result = this->SetParentElement(_parentElement, errors); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +bool Param::SetParentElement(ElementPtr _parentElement, sdf::Errors &_errors) { auto prevParentElement = this->dataPtr->parentElement; this->dataPtr->parentElement = _parentElement; - if (!this->Reparse()) + if (!this->Reparse(_errors)) { this->dataPtr->parentElement = prevParentElement; return false; @@ -1079,6 +1336,16 @@ void Param::Reset() ////////////////////////////////////////////////// bool Param::Reparse() +{ + sdf::Errors errors; + bool result = this->Reparse(errors); + if (!errors.empty()) + sdferr << errors; + return result; +} + +////////////////////////////////////////////////// +bool Param::Reparse(sdf::Errors &_errors) { std::string strToReparse; if (this->dataPtr->strValue.has_value()) @@ -1090,28 +1357,33 @@ bool Param::Reparse() else if (!this->dataPtr->StringFromValueImpl(PrintConfig(), this->dataPtr->typeName, this->dataPtr->defaultValue, - strToReparse)) + strToReparse, + _errors)) { - sdferr << "Failed to obtain string from default value during reparsing.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Failed to obtain string from default value during reparsing."}); return false; } if (!this->dataPtr->ValueFromStringImpl( - this->dataPtr->typeName, strToReparse, this->dataPtr->value)) + this->dataPtr->typeName, strToReparse, this->dataPtr->value, _errors)) { if (const auto parentElement = this->dataPtr->parentElement.lock()) { - sdferr << "Failed to set value '" << strToReparse - << "' to key [" << this->GetKey() - << "] for new parent element of name '" << parentElement->GetName() - << "', reverting to previous value '" - << this->GetAsString() << "'.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Failed to set value '" + strToReparse + + "' to key [" + this->GetKey() + + "] for new parent element of name '" + parentElement->GetName() + + "', reverting to previous value '" + + this->GetAsString(_errors) + "'."}); } else { - sdferr << "Failed to set value '" << strToReparse - << "' to key [" << this->GetKey() << "] without a parent element, " - << "reverting to previous value '" << this->GetAsString() << "'.\n"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, + "Failed to set value '" + strToReparse + + "' to key [" + this->GetKey() + "] without a parent element, " + + "reverting to previous value '" + + this->GetAsString(_errors) + "'."}); } return false; } @@ -1175,9 +1447,19 @@ bool Param::IgnoresParentElementAttribute() const ///////////////////////////////////////////////// bool Param::ValidateValue() const +{ + sdf::Errors errors; + bool result = this->ValidateValue(errors); + if (!errors.empty()) + sdferr << errors; + return result; +} + +///////////////////////////////////////////////// +bool Param::ValidateValue(sdf::Errors &_errors) const { return std::visit( - [this](const auto &_val) -> bool + [this, &_errors](const auto &_val) -> bool { using T = std::decay_t; // cppcheck-suppress syntaxError @@ -1188,10 +1470,12 @@ bool Param::ValidateValue() const { if (_val < std::get(*this->dataPtr->minValue)) { - sdferr << "The value [" << _val - << "] is less than the minimum allowed value of [" - << *this->GetMinValueAsString() << "] for key [" - << this->GetKey() << "]\n"; + std::ostringstream oss; + oss << "The value [" << _val + << "] is less than the minimum allowed value of [" + << *this->GetMinValueAsString() << "] for key [" + << this->GetKey() << "]"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, oss.str()}); return false; } } @@ -1199,10 +1483,12 @@ bool Param::ValidateValue() const { if (_val > std::get(*this->dataPtr->maxValue)) { - sdferr << "The value [" << _val - << "] is greater than the maximum allowed value of [" - << *this->GetMaxValueAsString() << "] for key [" - << this->GetKey() << "]\n"; + std::ostringstream oss; + oss << "The value [" << _val + << "] is greater than the maximum allowed value of [" + << *this->GetMaxValueAsString() << "] for key [" + << this->GetKey() << "]"; + _errors.push_back({ErrorCode::PARAMETER_ERROR, oss.str()}); return false; } } diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index d592c6c7b..88d6dd0c9 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -11,6 +11,7 @@ set(tests deprecated_specs.cc disable_fixed_joint_reduction.cc element_tracing.cc + error_output.cc fixed_joint_reduction.cc force_torque_sensor.cc frame.cc diff --git a/test/integration/error_output.cc b/test/integration/error_output.cc new file mode 100644 index 000000000..4e6ec2305 --- /dev/null +++ b/test/integration/error_output.cc @@ -0,0 +1,132 @@ +/* + * Copyright 2022 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 +#include + +#include + +#include "sdf/Element.hh" +#include "sdf/Error.hh" +#include "sdf/Param.hh" +#include "sdf/Types.hh" +#include "test_utils.hh" + +//////////////////////////////////////// +// Test Param class for sdf::Errors outputs +TEST(Error, ErrorOutput) +{ + std::stringstream buffer; + sdf::testing::RedirectConsoleStream redir( + sdf::Console::Instance()->GetMsgStream(), &buffer); + + sdf::Errors errors; + ASSERT_NO_THROW(sdf::Param param1("key", "not_valid_type", "true", false, + errors, "description")); + ASSERT_EQ(errors[0].Code(), sdf::ErrorCode::UNKNOWN_PARAMETER_TYPE); + ASSERT_NE(std::string::npos, + errors[0].Message().find( + "Unknown parameter type[not_valid_type]")); + ASSERT_EQ(errors[1].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, + errors[1].Message().find("Invalid parameter")); + + ASSERT_NO_THROW(sdf::Param param2("key", "not_valid_type", "true", + false, "", "", errors, "description")); + ASSERT_EQ(errors[2].Code(), sdf::ErrorCode::UNKNOWN_PARAMETER_TYPE); + ASSERT_NE(std::string::npos, + errors[2].Message().find("Unknown parameter type[not_valid_type]")); + ASSERT_EQ(errors[3].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, + errors[3].Message().find("Invalid parameter")); + + sdf::Param param3("key", "bool", "true", false, errors, "description"); + // Check no new errors were added + ASSERT_EQ(errors.size(), 4u); + param3.Set(4, errors); + ASSERT_EQ(errors[4].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, + errors[4].Message().find("Invalid boolean value")); + + ignition::math::Pose3d pose; + param3.Get(pose, errors); + ASSERT_EQ(errors[5].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[5].Message().find( + "The value for //pose[@rotation_format='euler_rpy'] must have 6 " + "values, but 1 were found instead in '1'.")); + + param3.Update(errors); + ASSERT_EQ(errors[6].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[6].Message().find( + "[updateFunc] is not set.")); + + sdf::Param requiredParam("key", "int", "1", true, "2", "4", errors, + "description"); + // Check no new errors were added + ASSERT_EQ(errors.size(), 7u); + requiredParam.SetFromString("", errors); + ASSERT_EQ(errors[7].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[7].Message().find( + "Empty string used when setting a required parameter. Key[key]")); + ASSERT_FALSE(requiredParam.ValidateValue(errors)); + ASSERT_EQ(errors[8].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[8].Message().find( + "The value [1] is less than the minimum allowed value of [2] for " + "key [key]")); + + + // Adding a parent with @rotation_format to something invalid + // will make reparse fail + sdf::Param poseParam("", "pose", "1 2 3 0.4 0.5 0.6", false, "description"); + sdf::ElementPtr poseElem(new sdf::Element); + poseElem->AddAttribute("rotation_format", "string", "invalid_format", false); + ASSERT_FALSE(poseParam.SetParentElement(poseElem, errors)); + ASSERT_EQ(errors[9].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[9].Message().find( + "Undefined attribute //pose[@rotation_format='invalid_format'], " + "only 'euler_rpy' and 'quat_xyzw' is supported.")); + ASSERT_EQ(errors[10].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[10].Message().find( + "Failed to set value '1 2 3 0.40000000000000002 0.5 " + "0.59999999999999987' to key [] for new parent element of name ''," + " reverting to previous value '1 2 3 0.40000000000000002 0.5 " + "0.59999999999999987'.")); + + sdf::Param param4("key", "bool", "15", false, "a", "b", errors, + "description"); + ASSERT_EQ(errors[11].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[11].Message().find( + "Invalid boolean value")); + ASSERT_EQ(errors[12].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[12].Message().find( + "Invalid parameter")); + ASSERT_EQ(errors[13].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[13].Message().find( + "Invalid boolean value")); + ASSERT_EQ(errors[14].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[14].Message().find( + "Invalid [min] parameter in SDFormat description of [key]")); + ASSERT_EQ(errors[15].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[15].Message().find( + "Invalid boolean value")); + ASSERT_EQ(errors[16].Code(), sdf::ErrorCode::PARAMETER_ERROR); + ASSERT_NE(std::string::npos, errors[16].Message().find( + "Invalid [max] parameter in SDFormat description of [key]")); + + // Check nothing has been printed + ASSERT_TRUE(buffer.str().empty()) << buffer.str(); +} From f9594acd2da5cd1b1fdf1497f938b0045f4cac98 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Wed, 4 May 2022 12:00:10 -0500 Subject: [PATCH 2/2] Suggestions for #939 Signed-off-by: Addisu Z. Taddese --- test/integration/error_output.cc | 108 ++++++++++++++++++------------- 1 file changed, 62 insertions(+), 46 deletions(-) diff --git a/test/integration/error_output.cc b/test/integration/error_output.cc index 4e6ec2305..085ecb27f 100644 --- a/test/integration/error_output.cc +++ b/test/integration/error_output.cc @@ -36,97 +36,113 @@ TEST(Error, ErrorOutput) sdf::Errors errors; ASSERT_NO_THROW(sdf::Param param1("key", "not_valid_type", "true", false, - errors, "description")); - ASSERT_EQ(errors[0].Code(), sdf::ErrorCode::UNKNOWN_PARAMETER_TYPE); - ASSERT_NE(std::string::npos, - errors[0].Message().find( - "Unknown parameter type[not_valid_type]")); - ASSERT_EQ(errors[1].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, - errors[1].Message().find("Invalid parameter")); + errors, "description")); + ASSERT_GE(2u, errors.size()); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::UNKNOWN_PARAMETER_TYPE); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "Unknown parameter type[not_valid_type]")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find("Invalid parameter")); + errors.clear(); ASSERT_NO_THROW(sdf::Param param2("key", "not_valid_type", "true", false, "", "", errors, "description")); - ASSERT_EQ(errors[2].Code(), sdf::ErrorCode::UNKNOWN_PARAMETER_TYPE); - ASSERT_NE(std::string::npos, - errors[2].Message().find("Unknown parameter type[not_valid_type]")); - ASSERT_EQ(errors[3].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, - errors[3].Message().find("Invalid parameter")); + ASSERT_GE(2u, errors.size()); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::UNKNOWN_PARAMETER_TYPE); + EXPECT_NE(std::string::npos, + errors[0].Message().find("Unknown parameter type[not_valid_type]")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find("Invalid parameter")); + errors.clear(); sdf::Param param3("key", "bool", "true", false, errors, "description"); // Check no new errors were added - ASSERT_EQ(errors.size(), 4u); + ASSERT_EQ(errors.size(), 0u); param3.Set(4, errors); - ASSERT_EQ(errors[4].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, - errors[4].Message().find("Invalid boolean value")); + ASSERT_GE(errors.size(), 1u); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find("Invalid boolean value")); + errors.clear(); ignition::math::Pose3d pose; param3.Get(pose, errors); - ASSERT_EQ(errors[5].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[5].Message().find( + ASSERT_GE(errors.size(), 1u); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[0].Message().find( "The value for //pose[@rotation_format='euler_rpy'] must have 6 " "values, but 1 were found instead in '1'.")); + errors.clear(); param3.Update(errors); - ASSERT_EQ(errors[6].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[6].Message().find( + ASSERT_GE(errors.size(), 1u); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[0].Message().find( "[updateFunc] is not set.")); + errors.clear(); sdf::Param requiredParam("key", "int", "1", true, "2", "4", errors, "description"); // Check no new errors were added - ASSERT_EQ(errors.size(), 7u); + ASSERT_EQ(errors.size(), 0u); requiredParam.SetFromString("", errors); - ASSERT_EQ(errors[7].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[7].Message().find( + ASSERT_GE(errors.size(), 1u); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[0].Message().find( "Empty string used when setting a required parameter. Key[key]")); - ASSERT_FALSE(requiredParam.ValidateValue(errors)); - ASSERT_EQ(errors[8].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[8].Message().find( + EXPECT_FALSE(requiredParam.ValidateValue(errors)); + ASSERT_GE(errors.size(), 2u); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[1].Message().find( "The value [1] is less than the minimum allowed value of [2] for " "key [key]")); + errors.clear(); // Adding a parent with @rotation_format to something invalid // will make reparse fail sdf::Param poseParam("", "pose", "1 2 3 0.4 0.5 0.6", false, "description"); sdf::ElementPtr poseElem(new sdf::Element); poseElem->AddAttribute("rotation_format", "string", "invalid_format", false); - ASSERT_FALSE(poseParam.SetParentElement(poseElem, errors)); - ASSERT_EQ(errors[9].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[9].Message().find( + EXPECT_FALSE(poseParam.SetParentElement(poseElem, errors)); + ASSERT_EQ(errors.size(), 2u); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[0].Message().find( "Undefined attribute //pose[@rotation_format='invalid_format'], " "only 'euler_rpy' and 'quat_xyzw' is supported.")); - ASSERT_EQ(errors[10].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[10].Message().find( + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[1].Message().find( "Failed to set value '1 2 3 0.40000000000000002 0.5 " "0.59999999999999987' to key [] for new parent element of name ''," " reverting to previous value '1 2 3 0.40000000000000002 0.5 " "0.59999999999999987'.")); + errors.clear(); sdf::Param param4("key", "bool", "15", false, "a", "b", errors, "description"); - ASSERT_EQ(errors[11].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[11].Message().find( + ASSERT_EQ(errors.size(), 6u); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[0].Message().find( "Invalid boolean value")); - ASSERT_EQ(errors[12].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[12].Message().find( + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[1].Message().find( "Invalid parameter")); - ASSERT_EQ(errors[13].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[13].Message().find( + EXPECT_EQ(errors[2].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[2].Message().find( "Invalid boolean value")); - ASSERT_EQ(errors[14].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[14].Message().find( + EXPECT_EQ(errors[3].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[3].Message().find( "Invalid [min] parameter in SDFormat description of [key]")); - ASSERT_EQ(errors[15].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[15].Message().find( + EXPECT_EQ(errors[4].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[4].Message().find( "Invalid boolean value")); - ASSERT_EQ(errors[16].Code(), sdf::ErrorCode::PARAMETER_ERROR); - ASSERT_NE(std::string::npos, errors[16].Message().find( + EXPECT_EQ(errors[5].Code(), sdf::ErrorCode::PARAMETER_ERROR); + EXPECT_NE(std::string::npos, errors[5].Message().find( "Invalid [max] parameter in SDFormat description of [key]")); // Check nothing has been printed - ASSERT_TRUE(buffer.str().empty()) << buffer.str(); + EXPECT_TRUE(buffer.str().empty()) << buffer.str(); }