Skip to content

Commit

Permalink
Port: 7 -> main (#540)
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <mjcarroll@intrinsic.ai>
  • Loading branch information
mjcarroll authored Aug 2, 2023
2 parents 92d6063 + 11bdf53 commit b7d2a60
Show file tree
Hide file tree
Showing 97 changed files with 214 additions and 1,949 deletions.
11 changes: 11 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ project(gz-math8 VERSION 8.0.0)
#============================================================================
# If you get an error at this line, you need to install gz-cmake
find_package(gz-cmake3 REQUIRED)
set(GZ_CMAKE_VER ${gz-cmake3_VERSION_MAJOR})

#============================================================================
# Configure the project
Expand Down Expand Up @@ -144,3 +145,13 @@ configure_file(${CMAKE_SOURCE_DIR}/tutorials.md.in ${CMAKE_BINARY_DIR}/tutorials
gz_create_docs(
API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md"
TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md")

#============================================================================
# Build examples
#============================================================================
if (BUILD_TESTING)
gz_build_examples(
SOURCE_DIR ${PROJECT_SOURCE_DIR}/examples
BINARY_DIR ${PROJECT_BINARY_DIR}/examples
)
endif()
40 changes: 36 additions & 4 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,22 +4,54 @@

## Gazebo Math 7.x

### Gazebo Math 7.1.0
### Gazebo Math 7.2.0 (2023-06-14)

1. Add tests to increase test coverage
* [Pull request #533](https://github.com/gazebosim/gz-math/pull/533)

1. Forward ports
* [Pull request #530](https://github.com/gazebosim/gz-math/pull/530)
* [Pull request #526](https://github.com/gazebosim/gz-math/pull/526)
* [Pull request #522](https://github.com/gazebosim/gz-math/pull/522)
* [Pull request #520](https://github.com/gazebosim/gz-math/pull/520)

1. Disable pybind11 on windows by default
* [Pull request #529](https://github.com/gazebosim/gz-math/pull/529)

1. Add option to skip pybind11 and SWIG
* [Pull request #480](https://github.com/gazebosim/gz-math/pull/480)

1. Custom PID error rate
* [Pull request #525](https://github.com/gazebosim/gz-math/pull/525)

1. Garden bazel support
* [Pull request #523](https://github.com/gazebosim/gz-math/pull/523)

1. Rename COPYING to LICENSE
* [Pull request #521](https://github.com/gazebosim/gz-math/pull/521)

1. Infrastructure
* [Pull request #519](https://github.com/gazebosim/gz-math/pull/519)

1. Fix link of installation tutorial to point to 7.1 version
* [Pull request #518](https://github.com/gazebosim/gz-math/pull/518)

### Gazebo Math 7.1.0 (2022-11-15)

1. Adds bounds retrieval for TimeVarying grid class.
* [Pull request #508](https://github.com/gazebosim/gz-math/pull/508)

### Gazebo Math 7.0.2
### Gazebo Math 7.0.2 (2022-09-26)

1. Update to disable tests failing on arm64
* [Pull request #512](https://github.com/gazebosim/gz-math/pull/512)

### Gazebo Math 7.0.1
### Gazebo Math 7.0.1 (2022-09-23)

1. Disable tests failing on arm64
* [Pull request #510](https://github.com/gazebosim/gz-math/pull/510)

### Gazebo Math 7.0.0
### Gazebo Math 7.0.0 (2022-09-22)

1. Deprecated `Angle::Degree(double)` and `Angle::Radian(double)`. Use `Angle::SetDegree(double)` and `Angle::SetRadian(double)` instead.
* [BitBucket pull request 326](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/326)
Expand Down
13 changes: 6 additions & 7 deletions examples/color_example.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,18 +18,17 @@
#include <iostream>
#include <gz/math/Color.hh>

int main(int argc, char **argv)
int main(int /*argc*/, char **/*argv*/)
{

//! [Create a color]
gz::math::Color a = gz::math::Color(0.3, 0.4, 0.5);
gz::math::Color a = gz::math::Color(0.3f, 0.4f, 0.5f);
//! [Create a color]
// The channel order is R, G, B, A and the default alpha value of a should be 1.0
std::cout << "The alpha value of a should be 1: " << a.A() << std::endl;



//! [Set a new color value]
a.gz::math::Color::Set(0.6, 0.7, 0.8, 1.0);
a.gz::math::Color::Set(0.6f, 0.7f, 0.8f, 1.0f);
//! [Set a new color value]
std::cout << "The RGBA value of a: " << a << std::endl;

Expand All @@ -41,8 +40,8 @@ int main(int argc, char **argv)

//! [Math operator]
std::cout << "Check if a is Blue: " << (a == gz::math::Color::Blue) << std::endl;
std::cout << "The RGB value of a should be (0, 0, 1): " << a[0] << ", "
<< a[1] << ", "
std::cout << "The RGB value of a should be (0, 0, 1): " << a[0] << ", "
<< a[1] << ", "
<< a[2] << std::endl;
//! [Math operator]

Expand Down
1 change: 0 additions & 1 deletion include/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,2 +1 @@
add_subdirectory(gz)
install(DIRECTORY ignition DESTINATION ${GZ_INCLUDE_INSTALL_DIR_FULL})
9 changes: 9 additions & 0 deletions include/gz/math/Box.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef GZ_MATH_BOX_HH_
#define GZ_MATH_BOX_HH_

#include <optional>
#include <gz/math/config.hh>
#include <gz/math/MassMatrix3.hh>
#include <gz/math/Material.hh>
Expand Down Expand Up @@ -189,6 +190,14 @@ namespace gz
/// could be due to an invalid size (<=0) or density (<=0).
public: bool MassMatrix(MassMatrix3<Precision> &_massMat) const;

/// \brief Get the mass matrix for this box. This function
/// is only meaningful if the box's size and material
/// have been set.
/// \return The computed mass matrix if parameters are valid
/// (radius > 0), (length > 0), and (density > 0). Otherwise
/// std::nullopt is returned.
public: std::optional< MassMatrix3<Precision> > MassMatrix() const;

/// \brief Get intersection between a plane and the box's edges.
/// Edges contained on the plane are ignored.
/// \param[in] _plane The plane against which we are testing intersection.
Expand Down
9 changes: 9 additions & 0 deletions include/gz/math/Cylinder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef GZ_MATH_CYLINDER_HH_
#define GZ_MATH_CYLINDER_HH_

#include <optional>
#include "gz/math/MassMatrix3.hh"
#include "gz/math/Material.hh"
#include "gz/math/Quaternion.hh"
Expand Down Expand Up @@ -115,6 +116,14 @@ namespace gz
/// (<=0).
public: bool MassMatrix(MassMatrix3d &_massMat) const;

/// \brief Get the mass matrix for this cylinder. This function
/// is only meaningful if the cylinder's radius, length, and material
/// have been set. Optionally, set the rotational offset.
/// \return The computed mass matrix if parameters are valid
/// (radius > 0), (length > 0) and (density > 0). Otherwise
/// std::nullopt is returned.
public: std::optional< MassMatrix3<Precision> > MassMatrix() const;

/// \brief Check if this cylinder is equal to the provided cylinder.
/// Radius, length, and material properties will be checked.
public: bool operator==(const Cylinder &_cylinder) const;
Expand Down
20 changes: 2 additions & 18 deletions include/gz/math/Helpers.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,6 @@
template <typename T>
constexpr T GZ_MASSMATRIX3_DEFAULT_TOLERANCE = T(10);

// TODO(CH3): Deprecated. Remove on tock.
template <typename T>
constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10);

/// \brief Define GZ_PI, GZ_PI_2, and GZ_PI_4.
/// This was put here for Windows support.
#ifdef M_PI
Expand Down Expand Up @@ -120,18 +116,6 @@ namespace gz
/// \brief size_t type with a value of 9
static const size_t GZ_NINE_SIZE_T = 9u;

// TODO(CH3): Deprecated. Remove on tock.
constexpr auto GZ_DEPRECATED(7) IGN_ZERO_SIZE_T = &GZ_ZERO_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_ONE_SIZE_T = &GZ_ONE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_TWO_SIZE_T = &GZ_TWO_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_THREE_SIZE_T = &GZ_THREE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_FOUR_SIZE_T = &GZ_FOUR_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_FIVE_SIZE_T = &GZ_FIVE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_SIX_SIZE_T = &GZ_SIX_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_SEVEN_SIZE_T = &GZ_SEVEN_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_EIGHT_SIZE_T = &GZ_EIGHT_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_NINE_SIZE_T = &GZ_NINE_SIZE_T;

/// \brief Double maximum value. This value will be similar to 1.79769e+308
static const double MAX_D = std::numeric_limits<double>::max();

Expand Down Expand Up @@ -353,7 +337,7 @@ namespace gz
T sum = 0;
for (unsigned int i = 0; i < _values.size(); ++i)
sum += _values[i];
return sum / _values.size();
return sum / static_cast<T>(_values.size());
}

/// \brief Get the variance of a vector of values.
Expand All @@ -367,7 +351,7 @@ namespace gz
T sum = 0;
for (unsigned int i = 0; i < _values.size(); ++i)
sum += (_values[i] - avg) * (_values[i] - avg);
return sum / _values.size();
return sum / static_cast<T>(_values.size());
}

/// \brief Get the maximum value of vector of values.
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/Polynomial3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,7 @@ namespace gz
using std::abs; // enable ADL
const T magnitude = abs(this->coeffs[i]);
const bool sign = this->coeffs[i] < T(0);
const int exponent = 3 - i;
const int exponent = 3 - static_cast<int>(i);
if (magnitude >= epsilon)
{
if (streamStarted)
Expand Down
8 changes: 8 additions & 0 deletions include/gz/math/Sphere.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef GZ_MATH_SPHERE_HH_
#define GZ_MATH_SPHERE_HH_

#include <optional>
#include "gz/math/MassMatrix3.hh"
#include "gz/math/Material.hh"
#include "gz/math/Quaternion.hh"
Expand Down Expand Up @@ -77,6 +78,13 @@ namespace gz
/// could be due to an invalid radius (<=0) or density (<=0).
public: bool MassMatrix(MassMatrix3d &_massMat) const;

/// \brief Get the mass matrix for this sphere. This function
/// is only meaningful if the sphere's radius and material have been set.
/// \return The computed mass matrix if parameters are valid
/// (radius > 0) and (density > 0). Otherwise
/// std::nullopt is returned.
public: std::optional< MassMatrix3<Precision> > MassMatrix() const;

/// \brief Check if this sphere is equal to the provided sphere.
/// Radius and material properties will be checked.
public: bool operator==(const Sphere &_sphere) const;
Expand Down
16 changes: 16 additions & 0 deletions include/gz/math/detail/Box.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include "gz/math/Triangle3.hh"

#include <optional>
#include <algorithm>
#include <set>
#include <utility>
Expand Down Expand Up @@ -310,6 +311,21 @@ bool Box<T>::MassMatrix(MassMatrix3<T> &_massMat) const
return _massMat.SetFromBox(this->material, this->size);
}

/////////////////////////////////////////////////
template<typename T>
std::optional< MassMatrix3<T> > Box<T>::MassMatrix() const
{
gz::math::MassMatrix3<T> _massMat;

if(!_massMat.SetFromBox(this->material, this->size))
{
return std::nullopt;
}
else
{
return std::make_optional(_massMat);
}
}

//////////////////////////////////////////////////
template<typename T>
Expand Down
21 changes: 21 additions & 0 deletions include/gz/math/detail/Cylinder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@
*/
#ifndef GZ_MATH_DETAIL_CYLINDER_HH_
#define GZ_MATH_DETAIL_CYLINDER_HH_

#include <optional>

namespace gz
{
namespace math
Expand Down Expand Up @@ -116,6 +119,24 @@ bool Cylinder<T>::MassMatrix(MassMatrix3d &_massMat) const
this->radius, this->rotOffset);
}

//////////////////////////////////////////////////
template<typename T>
std::optional < MassMatrix3<T> > Cylinder<T>::MassMatrix() const
{
gz::math::MassMatrix3<T> _massMat;

if(!_massMat.SetFromCylinderZ(
this->material, this->length,
this->radius, this->rotOffset))
{
return std::nullopt;
}
else
{
return std::make_optional(_massMat);
}
}

//////////////////////////////////////////////////
template<typename T>
T Cylinder<T>::Volume() const
Expand Down
18 changes: 18 additions & 0 deletions include/gz/math/detail/Sphere.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef GZ_MATH_DETAIL_SPHERE_HH_
#define GZ_MATH_DETAIL_SPHERE_HH_

#include <optional>
#include "gz/math/Sphere.hh"

namespace gz
Expand Down Expand Up @@ -88,6 +89,23 @@ bool Sphere<T>::MassMatrix(MassMatrix3d &_massMat) const
return _massMat.SetFromSphere(this->material, this->radius);
}

//////////////////////////////////////////////////
template<typename T>
std::optional < MassMatrix3<T> > Sphere<T>::MassMatrix() const
{
gz::math::MassMatrix3<T> _massMat;

if(!_massMat.SetFromSphere(this->material, this->radius))
{
return std::nullopt;
}
else
{
return std::make_optional(_massMat);
}
}


//////////////////////////////////////////////////
template<typename T>
T Sphere<T>::Volume() const
Expand Down
19 changes: 0 additions & 19 deletions include/ignition/math.hh

This file was deleted.

19 changes: 0 additions & 19 deletions include/ignition/math/AdditivelySeparableScalarField3.hh

This file was deleted.

Loading

0 comments on commit b7d2a60

Please sign in to comment.