Skip to content

Commit

Permalink
Renamed <moi_calculator_params> element to <auto_inertia_params>
Browse files Browse the repository at this point in the history
Signed-off-by: Jasmeet Singh <jasmeet0915@gmail.com>
  • Loading branch information
jasmeet0915 committed Aug 14, 2023
1 parent 7b2e37b commit 0f98215
Show file tree
Hide file tree
Showing 7 changed files with 26 additions and 19 deletions.
13 changes: 10 additions & 3 deletions include/sdf/Collision.hh
Original file line number Diff line number Diff line change
Expand Up @@ -87,9 +87,16 @@ namespace sdf
/// \param[in] _density Density of the collision.
public: void SetDensity(double _density);

public: sdf::ElementPtr MoiCalulatorParams() const;

public: void SetMoiCalculatorParams(const sdf::ElementPtr _calculatorParams);
/// \brief Get the ElementPtr to the <auto_inertia_params> element
/// This element can be used as a parent element to hold user-defined
/// params for the custom moment of inertia calculator.
/// \return ElementPtr object for the <auto_inertia_params> element.
public: sdf::ElementPtr AutoInertiaParams() const;

/// \brief Function to set the auto inertia params using a
/// sdf ElementPtr object
/// \param[in] _density Density of the collision.
public: void SetAutoInertiaParams(const sdf::ElementPtr _autoInertiaParams);

/// \brief Get a pointer to the collisions's geometry.
/// \return The collision's geometry.
Expand Down
2 changes: 1 addition & 1 deletion include/sdf/Geometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ namespace sdf
/// \return A std::optional with gz::math::Inertiald object or std::nullopt
public: std::optional<gz::math::Inertiald>
CalculateInertial(double _density, const ParserConfig &_config,
sdf::ElementPtr _calculatorParams);
sdf::ElementPtr _autoInertiaParams);

/// \brief Get a pointer to the SDF element that was used during
/// load.
Expand Down
2 changes: 1 addition & 1 deletion include/sdf/Mesh.hh
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ namespace sdf
/// \param[in] density Density of the mesh in kg/m^3
/// \return A std::optional with gz::math::Inertiald object or std::nullopt
public: std::optional<gz::math::Inertiald> CalculateInertial(const double _density,
const sdf::ElementPtr _calculatorParams, const ParserConfig &_config);
const sdf::ElementPtr _autoInertiaParams, const ParserConfig &_config);

/// \brief Get a pointer to the SDF element that was used during load.
/// \return SDF element pointer. The value will be nullptr if Load has
Expand Down
2 changes: 1 addition & 1 deletion sdf/1.11/collision.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
</description>
</element>

<element name="moi_calculator_params" required="0">
<element name="auto_inertia_params" required="0">
<description>Parent tag to hold user-defined custom params for mesh inertia calculator</description>
</element>

Expand Down
18 changes: 9 additions & 9 deletions src/Collision.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class sdf::Collision::Implementation
public: double density{1000.0};

/// \brief SDF element pointer to <moi_calculator_params> tag
public: sdf::ElementPtr moiCalculatorParams;
public: sdf::ElementPtr autoInertiaParams;

/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
Expand Down Expand Up @@ -149,15 +149,15 @@ void Collision::SetDensity(double _density)
}

/////////////////////////////////////////////////
sdf::ElementPtr Collision::MoiCalulatorParams() const
sdf::ElementPtr Collision::AutoInertiaParams() const
{
return this->dataPtr->moiCalculatorParams;
return this->dataPtr->autoInertiaParams;
}

/////////////////////////////////////////////////
void Collision::SetMoiCalculatorParams(const sdf::ElementPtr _calculatorParams)
void Collision::SetAutoInertiaParams(const sdf::ElementPtr _autoInertiaParams)
{
this->dataPtr->moiCalculatorParams = _calculatorParams;
this->dataPtr->autoInertiaParams = _autoInertiaParams;
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -256,15 +256,15 @@ Errors Collision::CalculateInertial(gz::math::Inertiald &_inertial,
);
}

if (this->dataPtr->sdf->HasElement("moi_calculator_params"))
if (this->dataPtr->sdf->HasElement("auto_inertia_params"))
{
this->dataPtr->moiCalculatorParams =
this->dataPtr->sdf->GetElement("moi_calculator_params");
this->dataPtr->autoInertiaParams =
this->dataPtr->sdf->GetElement("auto_inertia_params");
}

auto geomInertial =
this->dataPtr->geom.CalculateInertial(this->dataPtr->density, _config,
this->dataPtr->moiCalculatorParams);
this->dataPtr->autoInertiaParams);

if (!geomInertial)
{
Expand Down
4 changes: 2 additions & 2 deletions src/Geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,7 @@ void Geometry::SetPolylineShape(const std::vector<Polyline> &_polylines)
}

std::optional<gz::math::Inertiald> Geometry::CalculateInertial(
double _density, const ParserConfig &_config, sdf::ElementPtr _calculatorParams)
double _density, const ParserConfig &_config, sdf::ElementPtr _autoInertiaParams)
{
std::optional< gz::math::Inertiald > geomInertial;

Expand All @@ -332,7 +332,7 @@ std::optional<gz::math::Inertiald> Geometry::CalculateInertial(
geomInertial = this->dataPtr->sphere->CalculateInertial(_density);
break;
case GeometryType::MESH:
geomInertial = this->dataPtr->mesh->CalculateInertial(_density, _calculatorParams, _config);
geomInertial = this->dataPtr->mesh->CalculateInertial(_density, _autoInertiaParams, _config);
break;
default:
break;
Expand Down
4 changes: 2 additions & 2 deletions src/Mesh.cc
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ void Mesh::SetCenterSubmesh(const bool _center)

//////////////////////////////////////////////////
std::optional<gz::math::Inertiald> Mesh::CalculateInertial(const double _density,
const sdf::ElementPtr _calculatorParams, const ParserConfig &_config)
const sdf::ElementPtr _autoInertiaParams, const ParserConfig &_config)
{
sdf::Errors errors;

Expand All @@ -204,7 +204,7 @@ std::optional<gz::math::Inertiald> Mesh::CalculateInertial(const double _density
const auto &customCalculator = _config.CustomMoiCalculator();

sdf::InterfaceMoiCalculator calcInterface = InterfaceMoiCalculator(
_density, *this, _calculatorParams);
_density, *this, _autoInertiaParams);

return customCalculator(errors, calcInterface);
}
Expand Down

0 comments on commit 0f98215

Please sign in to comment.