Skip to content

Commit

Permalink
Use ImplPtr from ign-utils where relevant (#299)
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll authored Jan 11, 2022
1 parent 3cc9adb commit b7825df
Show file tree
Hide file tree
Showing 46 changed files with 306 additions and 938 deletions.
1 change: 1 addition & 0 deletions .github/ci/packages.apt
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
libeigen3-dev
libignition-cmake2-dev
libignition-utils1-dev
python3-distutils
python3-pybind11
ruby-dev
Expand Down
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,11 @@ option(USE_DIST_PACKAGES_FOR_PYTHON
# Search for project-specific dependencies
#============================================================================

#--------------------------------------
# Find ignition-utils
ign_find_package(ignition-utils1 REQUIRED VERSION 1.0)
set(IGN_UTILS_VER ${ignition-utils1_VERSION_MAJOR})

#--------------------------------------
# Find eigen3
ign_find_package(
Expand Down
19 changes: 2 additions & 17 deletions include/ignition/math/AxisAlignedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,17 +25,14 @@
#include <ignition/math/MassMatrix3.hh>
#include <ignition/math/Material.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/utils/ImplPtr.hh>

namespace ignition
{
namespace math
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_MATH_VERSION_NAMESPACE {
//
// Forward declaration of private data
class AxisAlignedBoxPrivate;

/// \class AxisAlignedBox AxisAlignedBox.hh ignition/math/AxisAlignedBox.hh
/// \brief Mathematical representation of a box that is aligned along
/// an X,Y,Z axis.
Expand Down Expand Up @@ -66,13 +63,6 @@ namespace ignition
public: AxisAlignedBox(double _vec1X, double _vec1Y, double _vec1Z,
double _vec2X, double _vec2Y, double _vec2Z);

/// \brief Copy Constructor
/// \param[in] _b AxisAlignedBox to copy
public: AxisAlignedBox(const AxisAlignedBox &_b);

/// \brief Destructor
public: ~AxisAlignedBox();

/// \brief Get the length along the x dimension
/// \return Double value of the length in the x dimension
public: double XLength() const;
Expand All @@ -97,11 +87,6 @@ namespace ignition
/// \param[in] _box AxisAlignedBox to add to this box
public: void Merge(const AxisAlignedBox &_box);

/// \brief Assignment operator. Set this box to the parameter
/// \param[in] _b AxisAlignedBox to copy
/// \return The new box.
public: AxisAlignedBox &operator=(const AxisAlignedBox &_b);

/// \brief Addition operator. result = this + _b
/// \param[in] _b AxisAlignedBox to add
/// \return The new box
Expand Down Expand Up @@ -287,7 +272,7 @@ namespace ignition
double &_low, double &_high) const;

/// \brief Private data pointer
private: AxisAlignedBoxPrivate *dataPtr;
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
7 changes: 0 additions & 7 deletions include/ignition/math/Box.hh
Original file line number Diff line number Diff line change
Expand Up @@ -91,13 +91,6 @@ namespace ignition
public: Box(const Vector3<Precision> &_size,
const ignition::math::Material &_mat);

/// \brief Copy Constructor.
/// \param[in] _b Box to copy.
public: Box(const Box<Precision> &_b) = default;

/// \brief Destructor.
public: ~Box() = default;

/// \brief Get the size of the box.
/// \return Size of the box in meters.
public: math::Vector3<Precision> Size() const;
Expand Down
3 changes: 0 additions & 3 deletions include/ignition/math/Cylinder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -67,9 +67,6 @@ namespace ignition
const Quaternion<Precision> &_rotOffset =
Quaternion<Precision>::Identity);

/// \brief Destructor
public: ~Cylinder() = default;

/// \brief Get the radius in meters.
/// \return The radius of the cylinder in meters.
public: Precision Radius() const;
Expand Down
20 changes: 2 additions & 18 deletions include/ignition/math/DiffDriveOdometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,10 @@
#define IGNITION_MATH_DIFFDRIVEODOMETRY_HH_

#include <chrono>
#include <memory>
#include <ignition/math/Angle.hh>
#include <ignition/math/Export.hh>
#include <ignition/math/config.hh>
#include <ignition/utils/ImplPtr.hh>

namespace ignition
{
Expand All @@ -32,10 +32,6 @@ namespace ignition

// Inline bracket to help doxygen filtering.
inline namespace IGNITION_MATH_VERSION_NAMESPACE {
//
// Forward declarations.
class DiffDriveOdometryPrivate;

/** \class DiffDriveOdometry DiffDriveOdometry.hh \
* ignition/math/DiffDriveOdometry.hh
**/
Expand Down Expand Up @@ -85,9 +81,6 @@ namespace ignition
/// velocity mean
public: explicit DiffDriveOdometry(size_t _windowSize = 10);

/// \brief Destructor.
public: ~DiffDriveOdometry();

/// \brief Initialize the odometry
/// \param[in] _time Current time.
public: void Init(const clock::time_point &_time);
Expand Down Expand Up @@ -137,17 +130,8 @@ namespace ignition
/// \param[in] _size The Velocity rolling window size.
public: void SetVelocityRollingWindowSize(size_t _size);

#ifdef _WIN32
// Disable warning C4251 which is triggered by
// std::unique_ptr
#pragma warning(push)
#pragma warning(disable: 4251)
#endif
/// \brief Private data pointer.
private: std::unique_ptr<DiffDriveOdometryPrivate> dataPtr;
#ifdef _WIN32
#pragma warning(pop)
#endif
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
19 changes: 2 additions & 17 deletions include/ignition/math/Frustum.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,16 +22,14 @@
#include <ignition/math/Plane.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/config.hh>
#include <ignition/utils/ImplPtr.hh>

namespace ignition
{
namespace math
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_MATH_VERSION_NAMESPACE {
//
// Forward declaration of private data
class FrustumPrivate;

/// \brief Mathematical representation of a frustum and related functions.
/// This is also known as a view frustum.
Expand Down Expand Up @@ -86,13 +84,6 @@ namespace ignition
double _aspectRatio,
const math::Pose3d &_pose = math::Pose3d::Zero);

/// \brief Copy Constructor
/// \param[in] _p Frustum to copy.
public: Frustum(const Frustum &_p);

/// \brief Destructor
public: ~Frustum();

/// \brief Get the near distance. This is the distance from the
/// frustum's vertex to the closest plane.
/// \return Near distance.
Expand Down Expand Up @@ -168,18 +159,12 @@ namespace ignition
/// \sa Pose
public: void SetPose(const Pose3d &_pose);

/// \brief Assignment operator. Set this frustum to the parameter.
/// \param[in] _f Frustum to copy
/// \return The new frustum.
public: Frustum &operator=(const Frustum &_f);

/// \brief Compute the planes of the frustum. This is called whenever
/// a property of the frustum is changed.
private: void ComputePlanes();

/// \internal
/// \brief Private data pointer
private: FrustumPrivate *dataPtr;
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
20 changes: 2 additions & 18 deletions include/ignition/math/GaussMarkovProcess.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
#define IGNITION_MATH_GAUSSMARKOVPROCESS_HH_

#include <chrono>
#include <memory>
#include <ignition/math/Export.hh>
#include <ignition/math/config.hh>
#include <ignition/utils/ImplPtr.hh>

namespace ignition
{
Expand All @@ -31,10 +31,6 @@ namespace ignition

// Inline bracket to help doxygen filtering.
inline namespace IGNITION_MATH_VERSION_NAMESPACE {
//
// Forward declarations.
class GaussMarkovProcessPrivate;

/** \class GaussMarkovProcess GaussMarkovProcess.hh\
* ignition/math/GaussMarkovProcess.hh
**/
Expand Down Expand Up @@ -64,9 +60,6 @@ namespace ignition
public: GaussMarkovProcess(double _start, double _theta, double _mu,
double _sigma);

/// \brief Destructor.
public: ~GaussMarkovProcess();

/// \brief Set the process parameters. This will also call Reset().
/// \param[in] _start The start value of the process.
/// \param[in] _theta The theta (\f$\theta\f$) parameter.
Expand Down Expand Up @@ -135,17 +128,8 @@ namespace ignition

public: double Update(double _dt);

#ifdef _WIN32
// Disable warning C4251 which is triggered by
// std::unique_ptr
#pragma warning(push)
#pragma warning(disable: 4251)
#endif
/// \brief Private data pointer.
private: std::unique_ptr<GaussMarkovProcessPrivate> dataPtr;
#ifdef _WIN32
#pragma warning(pop)
#endif
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
11 changes: 3 additions & 8 deletions include/ignition/math/Kmeans.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,14 @@
#include <ignition/math/Helpers.hh>
#include <ignition/math/config.hh>

#include <ignition/utils/ImplPtr.hh>

namespace ignition
{
namespace math
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_MATH_VERSION_NAMESPACE {
//
// Forward declare private data
class KmeansPrivate;

/// \class Kmeans Kmeans.hh math/gzmath.hh
/// \brief K-Means clustering algorithm. Given a set of observations,
Expand All @@ -43,9 +42,6 @@ namespace ignition
/// \param[in] _obs Set of observations to cluster.
public: explicit Kmeans(const std::vector<Vector3d> &_obs);

/// \brief Destructor.
public: virtual ~Kmeans();

/// \brief Get the observations to cluster.
/// \return The vector of observations.
public: std::vector<Vector3d> Observations() const;
Expand Down Expand Up @@ -80,8 +76,7 @@ namespace ignition
/// \return The index of the closest centroid to the point _p.
private: unsigned int ClosestCentroid(const Vector3d &_p) const;

/// \brief Private data pointer
private: KmeansPrivate *dataPtr;
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
28 changes: 2 additions & 26 deletions include/ignition/math/Material.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,15 +23,14 @@
#include <ignition/math/Export.hh>
#include <ignition/math/config.hh>
#include <ignition/math/MaterialType.hh>
#include <ignition/utils/ImplPtr.hh>

namespace ignition
{
namespace math
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_MATH_VERSION_NAMESPACE {
// Forward declarations
class MaterialPrivate;

/// \brief Contains information about a single material.
///
Expand Down Expand Up @@ -80,18 +79,6 @@ namespace ignition
/// \param[in] _density Material density.
public: explicit Material(const double _density);

/// \brief Copy constructor.
/// \param[in] _material Material to copy.
public: Material(const Material &_material);

/// \brief Move constructor.
/// \param[in] _material Material to move. The _material object will
/// have default values after the move.
public: Material(Material &&_material);

/// \brief Destructor.
public: ~Material();

/// \brief Get all the built-in materials.
/// \return A map of all the materials. The map's key is
/// material type and the map's value is the material object.
Expand All @@ -107,17 +94,6 @@ namespace ignition
const double _value,
const double _epsilon = std::numeric_limits<double>::max());

/// \brief Copy operator.
/// \param[in] _material Material to copy.
/// \return Reference to this material.
public: Material &operator=(const Material &_material);

/// \brief Move operator.
/// \param[in] _material Material to move. The _material object will
/// contain default values after this move.
/// \return Reference to this Material.
public: Material &operator=(Material &&_material);

/// \brief Equality operator. This compares type and density values.
/// \param[in] _material Material to evaluate this object against.
/// \return True if this material is equal to the given _material.
Expand Down Expand Up @@ -158,7 +134,7 @@ namespace ignition
public: void SetDensity(const double _density);

/// \brief Private data pointer.
private: MaterialPrivate *dataPtr = nullptr;
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
Loading

0 comments on commit b7825df

Please sign in to comment.