Skip to content

Commit 757ef4d

Browse files
authored
Merge branch 'gz-math7' into mjcarroll/examples_from_cmake
2 parents 9ebc6e6 + cf5d7f3 commit 757ef4d

File tree

17 files changed

+184
-20
lines changed

17 files changed

+184
-20
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
33
#============================================================================
44
# Initialize the project
55
#============================================================================
6-
project(gz-math7 VERSION 7.1.0)
6+
project(gz-math7 VERSION 7.2.0)
77

88
#============================================================================
99
# Find gz-cmake

Changelog.md

Lines changed: 36 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,21 +1,53 @@
11
## Gazebo Math 7.x
22

3-
### Gazebo Math 7.1.0
3+
### Gazebo Math 7.2.0 (2023-06-14)
4+
5+
1. Add tests to increase test coverage
6+
* [Pull request #533](https://github.com/gazebosim/gz-math/pull/533)
7+
8+
1. Forward ports
9+
* [Pull request #530](https://github.com/gazebosim/gz-math/pull/530)
10+
* [Pull request #526](https://github.com/gazebosim/gz-math/pull/526)
11+
* [Pull request #522](https://github.com/gazebosim/gz-math/pull/522)
12+
* [Pull request #520](https://github.com/gazebosim/gz-math/pull/520)
13+
14+
1. Disable pybind11 on windows by default
15+
* [Pull request #529](https://github.com/gazebosim/gz-math/pull/529)
16+
17+
1. Add option to skip pybind11 and SWIG
18+
* [Pull request #480](https://github.com/gazebosim/gz-math/pull/480)
19+
20+
1. Custom PID error rate
21+
* [Pull request #525](https://github.com/gazebosim/gz-math/pull/525)
22+
23+
1. Garden bazel support
24+
* [Pull request #523](https://github.com/gazebosim/gz-math/pull/523)
25+
26+
1. Rename COPYING to LICENSE
27+
* [Pull request #521](https://github.com/gazebosim/gz-math/pull/521)
28+
29+
1. Infrastructure
30+
* [Pull request #519](https://github.com/gazebosim/gz-math/pull/519)
31+
32+
1. Fix link of installation tutorial to point to 7.1 version
33+
* [Pull request #518](https://github.com/gazebosim/gz-math/pull/518)
34+
35+
### Gazebo Math 7.1.0 (2022-11-15)
436

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

8-
### Gazebo Math 7.0.2
40+
### Gazebo Math 7.0.2 (2022-09-26)
941

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

13-
### Gazebo Math 7.0.1
45+
### Gazebo Math 7.0.1 (2022-09-23)
1446

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

18-
### Gazebo Math 7.0.0
50+
### Gazebo Math 7.0.0 (2022-09-22)
1951

2052
1. Deprecated `Angle::Degree(double)` and `Angle::Radian(double)`. Use `Angle::SetDegree(double)` and `Angle::SetRadian(double)` instead.
2153
* [BitBucket pull request 326](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/326)

include/gz/math/Box.hh

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#ifndef GZ_MATH_BOX_HH_
1818
#define GZ_MATH_BOX_HH_
1919

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

193+
/// \brief Get the mass matrix for this box. This function
194+
/// is only meaningful if the box's size and material
195+
/// have been set.
196+
/// \return The computed mass matrix if parameters are valid
197+
/// (radius > 0), (length > 0), and (density > 0). Otherwise
198+
/// std::nullopt is returned.
199+
public: std::optional< MassMatrix3<Precision> > MassMatrix() const;
200+
192201
/// \brief Get intersection between a plane and the box's edges.
193202
/// Edges contained on the plane are ignored.
194203
/// \param[in] _plane The plane against which we are testing intersection.

include/gz/math/Cylinder.hh

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#ifndef GZ_MATH_CYLINDER_HH_
1818
#define GZ_MATH_CYLINDER_HH_
1919

20+
#include <optional>
2021
#include "gz/math/MassMatrix3.hh"
2122
#include "gz/math/Material.hh"
2223
#include "gz/math/Quaternion.hh"
@@ -115,6 +116,14 @@ namespace gz
115116
/// (<=0).
116117
public: bool MassMatrix(MassMatrix3d &_massMat) const;
117118

119+
/// \brief Get the mass matrix for this cylinder. This function
120+
/// is only meaningful if the cylinder's radius, length, and material
121+
/// have been set. Optionally, set the rotational offset.
122+
/// \return The computed mass matrix if parameters are valid
123+
/// (radius > 0), (length > 0) and (density > 0). Otherwise
124+
/// std::nullopt is returned.
125+
public: std::optional< MassMatrix3<Precision> > MassMatrix() const;
126+
118127
/// \brief Check if this cylinder is equal to the provided cylinder.
119128
/// Radius, length, and material properties will be checked.
120129
public: bool operator==(const Cylinder &_cylinder) const;

include/gz/math/Sphere.hh

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#ifndef GZ_MATH_SPHERE_HH_
1818
#define GZ_MATH_SPHERE_HH_
1919

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

81+
/// \brief Get the mass matrix for this sphere. This function
82+
/// is only meaningful if the sphere's radius and material have been set.
83+
/// \return The computed mass matrix if parameters are valid
84+
/// (radius > 0) and (density > 0). Otherwise
85+
/// std::nullopt is returned.
86+
public: std::optional< MassMatrix3<Precision> > MassMatrix() const;
87+
8088
/// \brief Check if this sphere is equal to the provided sphere.
8189
/// Radius and material properties will be checked.
8290
public: bool operator==(const Sphere &_sphere) const;

include/gz/math/detail/Box.hh

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include "gz/math/Triangle3.hh"
2121

22+
#include <optional>
2223
#include <algorithm>
2324
#include <set>
2425
#include <utility>
@@ -310,6 +311,21 @@ bool Box<T>::MassMatrix(MassMatrix3<T> &_massMat) const
310311
return _massMat.SetFromBox(this->material, this->size);
311312
}
312313

314+
/////////////////////////////////////////////////
315+
template<typename T>
316+
std::optional< MassMatrix3<T> > Box<T>::MassMatrix() const
317+
{
318+
gz::math::MassMatrix3<T> _massMat;
319+
320+
if(!_massMat.SetFromBox(this->material, this->size))
321+
{
322+
return std::nullopt;
323+
}
324+
else
325+
{
326+
return std::make_optional(_massMat);
327+
}
328+
}
313329

314330
//////////////////////////////////////////////////
315331
template<typename T>

include/gz/math/detail/Cylinder.hh

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,9 @@
1616
*/
1717
#ifndef GZ_MATH_DETAIL_CYLINDER_HH_
1818
#define GZ_MATH_DETAIL_CYLINDER_HH_
19+
20+
#include <optional>
21+
1922
namespace gz
2023
{
2124
namespace math
@@ -116,6 +119,24 @@ bool Cylinder<T>::MassMatrix(MassMatrix3d &_massMat) const
116119
this->radius, this->rotOffset);
117120
}
118121

122+
//////////////////////////////////////////////////
123+
template<typename T>
124+
std::optional < MassMatrix3<T> > Cylinder<T>::MassMatrix() const
125+
{
126+
gz::math::MassMatrix3<T> _massMat;
127+
128+
if(!_massMat.SetFromCylinderZ(
129+
this->material, this->length,
130+
this->radius, this->rotOffset))
131+
{
132+
return std::nullopt;
133+
}
134+
else
135+
{
136+
return std::make_optional(_massMat);
137+
}
138+
}
139+
119140
//////////////////////////////////////////////////
120141
template<typename T>
121142
T Cylinder<T>::Volume() const

include/gz/math/detail/Sphere.hh

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#ifndef GZ_MATH_DETAIL_SPHERE_HH_
1818
#define GZ_MATH_DETAIL_SPHERE_HH_
1919

20+
#include <optional>
2021
#include "gz/math/Sphere.hh"
2122

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

92+
//////////////////////////////////////////////////
93+
template<typename T>
94+
std::optional < MassMatrix3<T> > Sphere<T>::MassMatrix() const
95+
{
96+
gz::math::MassMatrix3<T> _massMat;
97+
98+
if(!_massMat.SetFromSphere(this->material, this->radius))
99+
{
100+
return std::nullopt;
101+
}
102+
else
103+
{
104+
return std::make_optional(_massMat);
105+
}
106+
}
107+
108+
91109
//////////////////////////////////////////////////
92110
template<typename T>
93111
T Sphere<T>::Volume() const

src/Box_TEST.cc

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -498,4 +498,10 @@ TEST(BoxTest, Mass)
498498
box.MassMatrix(massMat);
499499
EXPECT_EQ(expectedMassMat, massMat);
500500
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMat.Mass());
501+
502+
auto massMatOpt = box.MassMatrix();
503+
ASSERT_NE(std::nullopt, massMatOpt);
504+
EXPECT_EQ(expectedMassMat, *massMatOpt);
505+
EXPECT_EQ(expectedMassMat.DiagonalMoments(), massMatOpt->DiagonalMoments());
506+
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMatOpt->Mass());
501507
}

src/Cylinder_TEST.cc

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -136,4 +136,10 @@ TEST(CylinderTest, Mass)
136136
cylinder.MassMatrix(massMat);
137137
EXPECT_EQ(expectedMassMat, massMat);
138138
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMat.Mass());
139+
140+
auto massMatOpt = cylinder.MassMatrix();
141+
ASSERT_NE(std::nullopt, massMatOpt);
142+
EXPECT_EQ(expectedMassMat, *massMatOpt);
143+
EXPECT_EQ(expectedMassMat.DiagonalMoments(), massMatOpt->DiagonalMoments());
144+
EXPECT_DOUBLE_EQ(expectedMassMat.Mass(), massMatOpt->Mass());
139145
}

0 commit comments

Comments
 (0)