Skip to content

Commit

Permalink
adding errors parameters to Physics function calls
Browse files Browse the repository at this point in the history
Signed-off-by: Marco A. Gutierrez <[email protected]>
  • Loading branch information
Marco A. Gutierrez committed Oct 3, 2022
1 parent cda1953 commit 3b9585f
Show file tree
Hide file tree
Showing 2 changed files with 31 additions and 11 deletions.
8 changes: 8 additions & 0 deletions include/sdf/Physics.hh
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,14 @@ namespace sdf
/// \return SDF element pointer with updated physics values.
public: sdf::ElementPtr ToElement() const;

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

/// \brief Private data pointer.
GZ_UTILS_IMPL_PTR(dataPtr)
};
Expand Down
34 changes: 23 additions & 11 deletions src/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,10 @@ Errors Physics::Load(sdf::ElementPtr _sdf)
}

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

std::pair<std::string, bool> stringPair =
_sdf->Get<std::string>("type", this->dataPtr->type);
_sdf->Get<std::string>(errors, "type", this->dataPtr->type);
if (!stringPair.second)
{
errors.push_back({ErrorCode::ELEMENT_MISSING,
Expand All @@ -99,7 +99,7 @@ Errors Physics::Load(sdf::ElementPtr _sdf)
this->dataPtr->type = stringPair.first;

std::pair<double, bool> doublePair =
_sdf->Get<double>("max_step_size", this->dataPtr->stepSize);
_sdf->Get<double>(errors, "max_step_size", this->dataPtr->stepSize);
if (!doublePair.second)
{
errors.push_back({ErrorCode::ELEMENT_MISSING,
Expand All @@ -108,7 +108,8 @@ Errors Physics::Load(sdf::ElementPtr _sdf)
}
this->dataPtr->stepSize = doublePair.first;

doublePair = _sdf->Get<double>("real_time_factor", this->dataPtr->rtf);
doublePair = _sdf->Get<double>(
errors, "real_time_factor", this->dataPtr->rtf);
if (!doublePair.second)
{
errors.push_back({ErrorCode::ELEMENT_MISSING,
Expand All @@ -118,7 +119,7 @@ Errors Physics::Load(sdf::ElementPtr _sdf)
this->dataPtr->rtf = doublePair.first;

this->dataPtr->maxContacts =
_sdf->Get<int>("max_contacts", this->dataPtr->maxContacts).first;
_sdf->Get<int>(errors, "max_contacts", this->dataPtr->maxContacts).first;

return errors;
}
Expand Down Expand Up @@ -203,17 +204,28 @@ void Physics::SetMaxContacts(int _maxContacts)

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

/////////////////////////////////////////////////
sdf::ElementPtr Physics::ToElement(sdf::Errors &_errors) const
{
sdf::ElementPtr elem(new sdf::Element);
sdf::initFile("physics.sdf", elem);

elem->GetAttribute("name")->Set(this->Name());
elem->GetAttribute("default")->Set(this->IsDefault());
elem->GetAttribute("type")->Set(this->EngineType());
elem->GetAttribute("name")->Set(this->Name(), _errors);
elem->GetAttribute("default")->Set(this->IsDefault(), _errors);
elem->GetAttribute("type")->Set(this->EngineType(), _errors);

elem->GetElement("max_step_size")->Set(this->MaxStepSize());
elem->GetElement("real_time_factor")->Set(this->RealTimeFactor());
elem->GetElement("max_contacts")->Set(this->MaxContacts());
elem->GetElement("max_step_size", _errors)->Set(
this->MaxStepSize(), _errors);
elem->GetElement("real_time_factor", _errors)->Set(
this->RealTimeFactor(), _errors);
elem->GetElement("max_contacts", _errors)->Set(this->MaxContacts(), _errors);

/// \todo(nkoenig) Support engine specific parameters.

Expand Down

0 comments on commit 3b9585f

Please sign in to comment.