Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/gz-math7' into ahcorde/7_to_main…
Browse files Browse the repository at this point in the history
…/270723
  • Loading branch information
ahcorde committed Jul 27, 2023
2 parents 92d6063 + f64cb8c commit 8a5bb56
Show file tree
Hide file tree
Showing 25 changed files with 213 additions and 460 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
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
4 changes: 2 additions & 2 deletions include/gz/math/Helpers.hh
Original file line number Diff line number Diff line change
Expand Up @@ -353,7 +353,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 +367,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;

Check warning on line 322 in include/gz/math/detail/Box.hh

View check run for this annotation

Codecov / codecov/patch

include/gz/math/detail/Box.hh#L322

Added line #L322 was not covered by tests
}
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;

Check warning on line 132 in include/gz/math/detail/Cylinder.hh

View check run for this annotation

Codecov / codecov/patch

include/gz/math/detail/Cylinder.hh#L132

Added line #L132 was not covered by tests
}
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;

Check warning on line 100 in include/gz/math/detail/Sphere.hh

View check run for this annotation

Codecov / codecov/patch

include/gz/math/detail/Sphere.hh#L100

Added line #L100 was not covered by tests
}
else
{
return std::make_optional(_massMat);
}
}


//////////////////////////////////////////////////
template<typename T>
T Sphere<T>::Volume() const
Expand Down
6 changes: 6 additions & 0 deletions src/Box_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -498,4 +498,10 @@ TEST(BoxTest, Mass)
box.MassMatrix(massMat);
EXPECT_EQ(expectedMassMat, massMat);
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMat.Mass());

auto massMatOpt = box.MassMatrix();
ASSERT_NE(std::nullopt, massMatOpt);
EXPECT_EQ(expectedMassMat, *massMatOpt);
EXPECT_EQ(expectedMassMat.DiagonalMoments(), massMatOpt->DiagonalMoments());
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMatOpt->Mass());
}
6 changes: 6 additions & 0 deletions src/Cylinder_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -136,4 +136,10 @@ TEST(CylinderTest, Mass)
cylinder.MassMatrix(massMat);
EXPECT_EQ(expectedMassMat, massMat);
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMat.Mass());

auto massMatOpt = cylinder.MassMatrix();
ASSERT_NE(std::nullopt, massMatOpt);
EXPECT_EQ(expectedMassMat, *massMatOpt);
EXPECT_EQ(expectedMassMat.DiagonalMoments(), massMatOpt->DiagonalMoments());
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMatOpt->Mass());
}
6 changes: 6 additions & 0 deletions src/Sphere_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,12 @@ TEST(SphereTest, Mass)
sphere.MassMatrix(massMat);
EXPECT_EQ(expectedMassMat, massMat);
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMat.Mass());

auto massMatOpt = sphere.MassMatrix();
ASSERT_NE(std::nullopt, massMatOpt);
EXPECT_EQ(expectedMassMat, *massMatOpt);
EXPECT_EQ(expectedMassMat.DiagonalMoments(), massMatOpt->DiagonalMoments());
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMatOpt->Mass());
}

//////////////////////////////////////////////////
Expand Down
12 changes: 8 additions & 4 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -104,8 +104,12 @@ function(configure_build_install_location _library_name)
# Install into test folder in build space for unit tests to import
set_target_properties(${_library_name} PROPERTIES
# Use generator expression to avoid prepending a build type specific directory on Windows
LIBRARY_OUTPUT_DIRECTORY $<1:${CMAKE_CURRENT_BINARY_DIR}/test>
RUNTIME_OUTPUT_DIRECTORY $<1:${CMAKE_CURRENT_BINARY_DIR}/test>)
LIBRARY_OUTPUT_DIRECTORY $<1:${CMAKE_CURRENT_BINARY_DIR}/test/gz>
RUNTIME_OUTPUT_DIRECTORY $<1:${CMAKE_CURRENT_BINARY_DIR}/test/gz>)

# Touch an init file to mark this directory as a usable python module
file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/test/gz/)
file(TOUCH ${CMAKE_CURRENT_BINARY_DIR}/test/gz/__init__.py)

# Install library for actual use
install(TARGETS ${_library_name}
Expand Down Expand Up @@ -187,8 +191,8 @@ if (BUILD_TESTING)
endif()

set(_env_vars)
list(APPEND _env_vars "PYTHONPATH=${FAKE_INSTALL_PREFIX}/lib/python/")
list(APPEND _env_vars "LD_LIBRARY_PATH=${FAKE_INSTALL_PREFIX}/lib:$ENV{LD_LIBRARY_PATH}")
list(APPEND _env_vars "PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}/test")
list(APPEND _env_vars "LD_LIBRARY_PATH=${CMAKE_CURRENT_BINARY_DIR}/test:$ENV{LD_LIBRARY_PATH}")
set_tests_properties(${test}.py PROPERTIES
ENVIRONMENT "${_env_vars}")
endforeach()
Expand Down
16 changes: 11 additions & 5 deletions src/python_pybind11/src/Box.hh
Original file line number Diff line number Diff line change
Expand Up @@ -105,11 +105,17 @@ void defineMathBox(py::module &m, const std::string &typestr)
.def("set_density_from_mass",
&Class::SetDensityFromMass,
"Set the density of this box based on a mass value.")
.def("mass_matrix",
&Class::MassMatrix,
"Get the mass matrix for this box. This function "
"is only meaningful if the box's size and material "
"have been set.")
.def("mass_matrix",
py::overload_cast<>(&Class::MassMatrix, py::const_),
"Get the mass matrix for this box. This function "
"is only meaningful if the box's size and material "
"have been set.")
.def("mass_matrix",
py::overload_cast<gz::math::MassMatrix3<T>&>
(&Class::MassMatrix, py::const_),
"Get the mass matrix for this box. This function "
"is only meaningful if the box's size and material "
"have been set.")
.def("intersections",
[](const Class &self, const Plane<T> &_plane)
{
Expand Down
Loading

0 comments on commit 8a5bb56

Please sign in to comment.