Skip to content

Commit

Permalink
Defer Material::Predefined construction to avoid static initialization (
Browse files Browse the repository at this point in the history
#290)

Switch the storage for the pre-defined list to be constexpr.

Also fix include guard spellings.

Signed-off-by: Jeremy Nimmer <[email protected]>

Co-authored-by: Michael Carroll <[email protected]>
  • Loading branch information
jwnimmer-tri and mjcarroll authored Dec 2, 2021
1 parent 2863a9a commit a3f59b4
Show file tree
Hide file tree
Showing 4 changed files with 62 additions and 40 deletions.
9 changes: 6 additions & 3 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,15 @@

1. Defer regex construction to avoid static initialization.
* [Pull request 289](https://github.com/ignitionrobotics/ign-math/pull/289)

1. Defer Material::Predefined construction to avoid static initialization.
* [Pull request 290](https://github.com/ignitionrobotics/ign-math/pull/290)

1. Resolve cppcheck errors by adding explicit constructors and consts.
* [Pull request 291](https://github.com/ignitionrobotics/ign-math/pull/291)

1. Remove virtual from destructors of copyable classes.
* [Pull request 293](https://github.com/ignitionrobotics/ign-math/pull/293)

1. Resolve cppcheck errors by adding explicit constructors and consts.
* [Pull request 291](https://github.com/ignitionrobotics/ign-math/pull/291)

## Ignition Math 6.x

Expand Down
4 changes: 2 additions & 2 deletions include/ignition/math/MaterialType.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
* limitations under the License.
*
*/
#ifndef IGNITION_MATH_MATERIALTYPES_HH_
#define IGNITION_MATH_MATERIALTYPES_HH_
#ifndef IGNITION_MATH_MATERIALTYPE_HH_
#define IGNITION_MATH_MATERIALTYPE_HH_

#include <ignition/math/Export.hh>
#include <ignition/math/config.hh>
Expand Down
71 changes: 44 additions & 27 deletions src/Material.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,10 @@
*/

#include "ignition/math/Material.hh"

#include <algorithm>
#include <memory>

#include "ignition/math/Helpers.hh"

// Placing the kMaterialData in a separate file for conveniece and clarity.
Expand All @@ -24,24 +28,17 @@
using namespace ignition;
using namespace math;

// Initialize the static map of Material objects based on the kMaterialData.
static const std::map<MaterialType, Material> kMaterials = []()
// Private data for the Material class
class ignition::math::MaterialPrivate
{
std::map<MaterialType, Material> matMap;

for (const std::pair<MaterialType, MaterialData> &mat : kMaterialData)
/// \brief Set from a kMaterialData constant.
public: void SetFrom(const std::pair<MaterialType, MaterialData>& _input)
{
matMap[mat.first].SetType(mat.first);
matMap[mat.first].SetName(mat.second.name);
matMap[mat.first].SetDensity(mat.second.density);
type = _input.first;
name = _input.second.name;
density = _input.second.density;
}

return matMap;
}();

// Private data for the Material class
class ignition::math::MaterialPrivate
{
/// \brief The material type.
public: MaterialType type = MaterialType::UNKNOWN_MATERIAL;

Expand All @@ -63,11 +60,13 @@ Material::Material()
Material::Material(const MaterialType _type)
: dataPtr(new MaterialPrivate)
{
if (kMaterials.find(_type) != kMaterials.end())
auto iter = std::find_if(std::begin(kMaterialData), std::end(kMaterialData),
[_type](const auto& item) {
return item.first == _type;
});
if (iter != std::end(kMaterialData))
{
this->dataPtr->type = _type;
this->dataPtr->name = kMaterials.at(_type).Name();
this->dataPtr->density = kMaterials.at(_type).Density();
this->dataPtr->SetFrom(*iter);
}
}

Expand All @@ -79,12 +78,13 @@ Material::Material(const std::string &_typename)
std::string material = _typename;
std::transform(material.begin(), material.end(), material.begin(), ::tolower);

for (const std::pair<MaterialType, Material> &mat : kMaterials)
auto iter = std::find_if(std::begin(kMaterialData), std::end(kMaterialData),
[&material](const auto& item) {
return item.second.name == material;
});
if (iter != std::end(kMaterialData))
{
if (mat.second.Name() == material)
{
*this = mat.second;
}
this->dataPtr->SetFrom(*iter);
}
}

Expand Down Expand Up @@ -121,7 +121,24 @@ Material::~Material()
///////////////////////////////
const std::map<MaterialType, Material> &Material::Predefined()
{
return kMaterials;
using Map = std::map<MaterialType, Material>;

// Initialize the static map of Material objects based on the kMaterialData.
// We construct upon first use and never destroy it, in order to avoid the
// [Static Initialization Order Fiasco](https://en.cppreference.com/w/cpp/language/siof).
static const Map * const kMaterials = []()
{
auto temporary = std::make_unique<Map>();
for (const auto &item : kMaterialData)
{
MaterialType type = item.first;
Material& material = (*temporary)[type];
material.dataPtr->SetFrom(item);
}
return temporary.release();
}();

return *kMaterials;
}

///////////////////////////////
Expand Down Expand Up @@ -198,13 +215,13 @@ void Material::SetToNearestDensity(const double _value, const double _epsilon)
double min = MAX_D;
Material result;

for (const std::pair<MaterialType, Material> &mat : kMaterials)
for (const auto &item : kMaterialData)
{
double diff = std::fabs(mat.second.Density() - _value);
double diff = std::fabs(item.second.density - _value);
if (diff < min && diff < _epsilon)
{
min = diff;
result = mat.second;
result.dataPtr->SetFrom(item);
}
}

Expand Down
18 changes: 10 additions & 8 deletions src/MaterialType.hh
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@
* limitations under the License.
*
*/
#ifndef IGNITION_MATERIAL_HH_
#define IGNITION_MATERIAL_HH_
#ifndef IGNITION_MATH_SRC_MATERIAL_TYPE_HH_
#define IGNITION_MATH_SRC_MATERIAL_TYPE_HH_

#include <map>
#include <string>
#include <array>
#include <utility>

using namespace ignition;
using namespace math;
Expand All @@ -27,17 +27,19 @@ using namespace math;
struct MaterialData
{
// Name of the material
std::string name;
// cppcheck-suppress unusedStructMember
const char * const name;

// Density of the material
// cppcheck-suppress unusedStructMember
double density;
const double density;
};

// The mapping of material type to name and density values.
// If you modify this map, make sure to also modify the MaterialType enum in
// include/ignition/math/MaterialTypes.hh
static std::map<MaterialType, MaterialData> kMaterialData =
// include/ignition/math/MaterialTypes.hh. The compiler will also complain if
// you forget to change the std::array<..., N> compile-time size constant.
constexpr std::array<std::pair<MaterialType, MaterialData>, 13> kMaterialData =
{{
{MaterialType::STYROFOAM, {"styrofoam", 75.0}},
{MaterialType::PINE, {"pine", 373.0}},
Expand Down

0 comments on commit a3f59b4

Please sign in to comment.