Skip to content

Commit

Permalink
Resolve cppcheck errors by adding explicit constructors and consts (#291
Browse files Browse the repository at this point in the history
)

Resolve cppcheck errors by adding explicit constructors and consts

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 1366e82 commit efd9c9f
Show file tree
Hide file tree
Showing 10 changed files with 18 additions and 9 deletions.
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@

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/OrientedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -126,15 +126,15 @@ namespace ignition
/// \brief Set the box size.
/// \param[in] _size Box size, in its own coordinate frame. Its absolute
/// value will be taken, so the size is non-negative.
public: void Size(Vector3<T> &_size)
public: void Size(const Vector3<T> &_size)
{
// Enforce non-negative size
this->size = _size.Abs();
}

/// \brief Set the box pose.
/// \param[in] _pose Box pose.
public: void Pose(Pose3<T> &_pose)
public: void Pose(const Pose3<T> &_pose)
{
this->pose = _pose;
}
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/math/Plane.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace ignition
/// \brief Constructor from a normal and a distance
/// \param[in] _normal The plane normal
/// \param[in] _offset Offset along the normal
public: Plane(const Vector3<T> &_normal, T _offset = 0.0)
public: explicit Plane(const Vector3<T> &_normal, T _offset = 0.0)
: normal(_normal), d(_offset)
{
}
Expand Down
10 changes: 5 additions & 5 deletions include/ignition/math/SemanticVersion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,11 +63,11 @@ namespace ignition
/// \param[in] _patch The patch number
/// \param[in] _prerelease The prerelease string
/// \param[in] _build The build metadata string
public: SemanticVersion(const unsigned int _major,
const unsigned int _minor = 0,
const unsigned int _patch = 0,
const std::string &_prerelease = "",
const std::string &_build = "");
public: explicit SemanticVersion(const unsigned int _major,
const unsigned int _minor = 0,
const unsigned int _patch = 0,
const std::string &_prerelease = "",
const std::string &_build = "");

/// \brief Destructor
public: ~SemanticVersion();
Expand Down
1 change: 1 addition & 0 deletions include/ignition/math/graph/Edge.hh
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ namespace graph
/// \param[in] _vertices The vertices of the edge.
/// \param[in] _data The data stored in the edge.
/// \param[in] _weight The weight (cost) of the edge.
// cppcheck-suppress noExplicitConstructor
EdgeInitializer(const VertexId_P &_vertices,
const E &_data = E(),
const double _weight = 1)
Expand Down
1 change: 1 addition & 0 deletions include/ignition/math/graph/GraphAlgorithms.hh
Original file line number Diff line number Diff line change
Expand Up @@ -340,6 +340,7 @@ namespace graph
// Add all vertices.
for (auto const &vPair : _graph.Vertices())
{
// cppcheck-suppress useStlAlgorithm
vertices.push_back(vPair.second.get());
}

Expand Down
1 change: 1 addition & 0 deletions include/ignition/math/graph/Vertex.hh
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ namespace graph
/// \param[in] _name Non-unique vertex name.
/// \param[in] _data User information.
/// \param[in] _id Optional unique id.
// cppcheck-suppress noExplicitConstructor
public: Vertex(const std::string &_name,
const V &_data = V(),
const VertexId _id = kNullId)
Expand Down
1 change: 1 addition & 0 deletions src/Frustum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,7 @@ bool Frustum::Contains(const Vector3d &_p) const
// visible.
for (auto const &plane : this->dataPtr->planes)
{
// cppcheck-suppress useStlAlgorithm
if (plane.Side(_p) == Planed::NEGATIVE_SIDE)
return false;
}
Expand Down
3 changes: 3 additions & 0 deletions src/Kmeans_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,10 @@ TEST(KmeansTest, Kmeans)

// ::SetObservations()
for (auto &elem : obsCopy)
{
// cppcheck-suppress useStlAlgorithm
elem += math::Vector3d(0.1, 0.2, 0.0);
}

EXPECT_TRUE(kmeans.Observations(obsCopy));

Expand Down
1 change: 0 additions & 1 deletion src/Temperature_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,6 @@ TEST(TemperatureTest, Operators)
EXPECT_NEAR(temp(), 30, 1e-6);

Temperature temp2 = temp;
// cppcheck-suppress knownConditionTrueFalse
EXPECT_TRUE(temp == temp2);

EXPECT_NEAR((temp + temp2).Kelvin(), 60, 1e-6);
Expand Down

0 comments on commit efd9c9f

Please sign in to comment.