Skip to content

Commit

Permalink
Merge branch 'ign-math6' into LolaSegura/add_material-type_material
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde committed Oct 6, 2021
2 parents c216a05 + 23a24d7 commit 53a6420
Show file tree
Hide file tree
Showing 77 changed files with 6,874 additions and 93 deletions.
14 changes: 12 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
#============================================================================
# Initialize the project
#============================================================================
project(ignition-math6 VERSION 6.8.0)
project(ignition-math6 VERSION 6.9.1)

#============================================================================
# Find ignition-cmake
Expand All @@ -21,8 +21,17 @@ ign_configure_project(VERSION_SUFFIX)
# Set project-specific options
#============================================================================

# ignition-math currently has no options that are unique to it
option(USE_SYSTEM_PATHS_FOR_RUBY_INSTALLATION
"Install ruby modules in standard system paths in the system"
OFF)

option(USE_SYSTEM_PATHS_FOR_PYTHON_INSTALLATION
"Install python modules in standard system paths in the system"
OFF)

option(USE_DIST_PACKAGES_FOR_PYTHON
"Use dist-packages instead of site-package to install python modules"
OFF)

#============================================================================
# Search for project-specific dependencies
Expand Down Expand Up @@ -60,6 +69,7 @@ if (SWIG_FOUND)

########################################
# Include python
find_package(PythonInterp 3 REQUIRED) # change to Python3 when Bionic is EOL
find_package(PythonLibs QUIET)
if (NOT PYTHONLIBS_FOUND)
message (STATUS "Searching for Python - not found.")
Expand Down
73 changes: 73 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,79 @@

## Ignition Math 6.x.x

## Ignition Math 6.9.1 (2021-09-30)

1. Avoid assertAlmostEqual for python strings
* [Pull request #255](https://github.com/ignitionrobotics/ign-math/pull/255)

1. Pose3_TEST.py: use 0.01 (not 0) in string test
* [Pull request #257](https://github.com/ignitionrobotics/ign-math/pull/257)

## Ignition Math 6.9.0 (2021-09-28)

1. Volume below a plane for spheres and boxes
* [Pull request #219](https://github.com/ignitionrobotics/ign-math/pull/219)

1. 🌐 Spherical coordinates: bug fix, docs and sanity checks
* [Pull request #235](https://github.com/ignitionrobotics/ign-math/pull/235)

1. Add Vector(2|3|4)<T>::NaN to easily create invalid vectors
* [Pull request #222](https://github.com/ignitionrobotics/ign-math/pull/222)

1. Add options to install python/ruby in system standard paths
* [Pull request #236](https://github.com/ignitionrobotics/ign-math/pull/236)

1. Add eigen utils to convert mesh 3d vertices to oriented box
* [Pull request #224](https://github.com/ignitionrobotics/ign-math/pull/224)

1. Python interface

1. Adds python interface to RollingMean, Color and Spline
* [Pull request #218](https://github.com/ignitionrobotics/ign-math/pull/218)

1. Adds python interface for Kmeans and Vector3Stats
* [Pull request #232](https://github.com/ignitionrobotics/ign-math/pull/232)

1. Adds python interface to PID and SemanticVersion.
* [Pull request #229](https://github.com/ignitionrobotics/ign-math/pull/229)

1. Adds python interface to triangle.
* [Pull request #231](https://github.com/ignitionrobotics/ign-math/pull/231)

1. Adds Line2, Line3, SignalStats, Temperature python interface
* [Pull request #220](https://github.com/ignitionrobotics/ign-math/pull/220)

1. Python interface: Renames methods to match PEP8 style
* [Pull request #226](https://github.com/ignitionrobotics/ign-math/pull/226)

1. Adds python interface to Filter, MovingWindowFilter, RotationSpline.
* [Pull request #230](https://github.com/ignitionrobotics/ign-math/pull/230)

1. Adds python interface to Quaternion, Pose3, Matrix3 and Matrix4
* [Pull request #221](https://github.com/ignitionrobotics/ign-math/pull/221)

1. Basic setup for Python interface using SWIG
* [Pull request #216](https://github.com/ignitionrobotics/ign-math/pull/216)
* [Pull request #223](https://github.com/ignitionrobotics/ign-math/pull/223)
* [Pull request #208](https://github.com/ignitionrobotics/ign-math/pull/208)
* [Pull request #239](https://github.com/ignitionrobotics/ign-math/pull/239)

1. 👩‍🌾 Don't use std::pow with integers in Vectors and handle sqrt
* [Pull request #207](https://github.com/ignitionrobotics/ign-math/pull/207)

1. Relax expectations about zero in SpeedLimiter_TEST to make ARM happy
* [Pull request #204](https://github.com/ignitionrobotics/ign-math/pull/204)

1. Infrastructure
* [Pull request #242](https://github.com/ignitionrobotics/ign-math/pull/242)
* [Pull request #217](https://github.com/ignitionrobotics/ign-math/pull/217)
* [Pull request #211](https://github.com/ignitionrobotics/ign-math/pull/211)
* [Pull request #209](https://github.com/ignitionrobotics/ign-math/pull/209)
* [Pull request #227](https://github.com/ignitionrobotics/ign-math/pull/227)
* [Pull request #225](https://github.com/ignitionrobotics/ign-math/pull/225)
* [Pull request #252](https://github.com/ignitionrobotics/ign-math/pull/252)
* [Pull request #253](https://github.com/ignitionrobotics/ign-math/pull/253)

## Ignition Math 6.8.0 (2021-03-30)

1. Add speed limiter class
Expand Down
7 changes: 7 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,13 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Ignition Math 6.8 to 6.9

1. **SphericalCoordinates**: A bug related to the LOCAL frame was fixed. To
preserve behaviour, the `LOCAL` frame was left with the bug, and a new
`LOCAL2` frame was introduced, which can be used to get the correct
calculations.

## Ignition Math 4.X to 5.X

### Additions
Expand Down
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@ ign-math
├── include/ignition/math Header files.
├── src Source files and unit tests.
│   └── graph Source files for the graph classes.
│   └── python SWIG Python interfaces.
│   └── ruby SWIG Ruby interfaces.
├── eigen3 Files for Eigen component.
├── test
│ ├── integration Integration tests.
Expand Down
6 changes: 3 additions & 3 deletions eigen3/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@ package(

licenses(["notice"])

public_headers = [
"include/ignition/math/eigen3/Conversions.hh",
]
public_headers = glob([
"include/ignition/math/eigen3/*.hh",
])

cc_library(
name = "eigen3",
Expand Down
161 changes: 161 additions & 0 deletions eigen3/include/ignition/math/eigen3/Util.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,161 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef IGNITION_MATH_EIGEN3_UTIL_HH_
#define IGNITION_MATH_EIGEN3_UTIL_HH_

#include <vector>

#include <Eigen/Geometry>
#include <Eigen/Eigenvalues>

#include <ignition/math/AxisAlignedBox.hh>
#include <ignition/math/Matrix3.hh>
#include <ignition/math/OrientedBox.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/eigen3/Conversions.hh>

namespace ignition
{
namespace math
{
namespace eigen3
{
/// \brief Get covariance matrix from a set of 3d vertices
/// https://github.com/isl-org/Open3D/blob/76c2baf9debd460900f056a9b51e9a80de9c0e64/cpp/open3d/utility/Eigen.cpp#L305
/// \param[in] _vertices a vector of 3d vertices
/// \return Covariance matrix
inline Eigen::Matrix3d covarianceMatrix(
const std::vector<math::Vector3d> &_vertices)
{
if (_vertices.empty())
return Eigen::Matrix3d::Identity();

Eigen::Matrix<double, 9, 1> cumulants;
cumulants.setZero();
for (const auto &vertex : _vertices)
{
const Eigen::Vector3d &point = math::eigen3::convert(vertex);
cumulants(0) += point(0);
cumulants(1) += point(1);
cumulants(2) += point(2);
cumulants(3) += point(0) * point(0);
cumulants(4) += point(0) * point(1);
cumulants(5) += point(0) * point(2);
cumulants(6) += point(1) * point(1);
cumulants(7) += point(1) * point(2);
cumulants(8) += point(2) * point(2);
}

Eigen::Matrix3d covariance;

cumulants /= static_cast<double>(_vertices.size());

covariance(0, 0) = cumulants(3) - cumulants(0) * cumulants(0);
covariance(1, 1) = cumulants(6) - cumulants(1) * cumulants(1);
covariance(2, 2) = cumulants(8) - cumulants(2) * cumulants(2);
covariance(0, 1) = cumulants(4) - cumulants(0) * cumulants(1);
covariance(1, 0) = covariance(0, 1);
covariance(0, 2) = cumulants(5) - cumulants(0) * cumulants(2);
covariance(2, 0) = covariance(0, 2);
covariance(1, 2) = cumulants(7) - cumulants(1) * cumulants(2);
covariance(2, 1) = covariance(1, 2);
return covariance;
}

/// \brief Get the oriented 3d bounding box of a set of 3d
/// vertices using PCA
/// http://codextechnicanum.blogspot.com/2015/04/find-minimum-oriented-bounding-box-of.html
/// \param[in] _vertices a vector of 3d vertices
/// \return Oriented 3D box
inline ignition::math::OrientedBoxd verticesToOrientedBox(
const std::vector<math::Vector3d> &_vertices)
{
math::OrientedBoxd box;

// Return an empty box if there are no vertices
if (_vertices.empty())
return box;

math::Vector3d mean;
for (const auto &point : _vertices)
mean += point;
mean /= static_cast<double>(_vertices.size());

Eigen::Vector3d centroid = math::eigen3::convert(mean);
Eigen::Matrix3d covariance = covarianceMatrix(_vertices);

// Eigen Vectors
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d>
eigenSolver(covariance, Eigen::ComputeEigenvectors);
Eigen::Matrix3d eigenVectorsPCA = eigenSolver.eigenvectors();

// This line is necessary for proper orientation in some cases.
// The numbers come out the same without it, but the signs are
// different and the box doesn't get correctly oriented in some cases.
eigenVectorsPCA.col(2) =
eigenVectorsPCA.col(0).cross(eigenVectorsPCA.col(1));

// Transform the original cloud to the origin where the principal
// components correspond to the axes.
Eigen::Matrix4d projectionTransform(Eigen::Matrix4d::Identity());
projectionTransform.block<3, 3>(0, 0) = eigenVectorsPCA.transpose();
projectionTransform.block<3, 1>(0, 3) =
-1.0f * (projectionTransform.block<3, 3>(0, 0) * centroid);

Eigen::Vector3d minPoint(INF_I32, INF_I32, INF_I32);
Eigen::Vector3d maxPoint(-INF_I32, -INF_I32, -INF_I32);

// Get the minimum and maximum points of the transformed cloud.
for (const auto &point : _vertices)
{
Eigen::Vector4d pt(0, 0, 0, 1);
pt.head<3>() = math::eigen3::convert(point);
Eigen::Vector4d tfPoint = projectionTransform * pt;
minPoint = minPoint.cwiseMin(tfPoint.head<3>());
maxPoint = maxPoint.cwiseMax(tfPoint.head<3>());
}

const Eigen::Vector3d meanDiagonal = 0.5f * (maxPoint + minPoint);

// quaternion is calculated using the eigenvectors (which determines
// how the final box gets rotated), and the transform to put the box
// in correct location is calculated
const Eigen::Quaterniond bboxQuaternion(eigenVectorsPCA);
const Eigen::Vector3d bboxTransform =
eigenVectorsPCA * meanDiagonal + centroid;

math::Vector3d size(
maxPoint.x() - minPoint.x(),
maxPoint.y() - minPoint.y(),
maxPoint.z() - minPoint.z()
);
math::Pose3d pose;
pose.Rot() = math::eigen3::convert(bboxQuaternion);
pose.Pos() = math::eigen3::convert(bboxTransform);

box.Size(size);
box.Pose(pose);
return box;
}
}
}
}

#endif
Loading

0 comments on commit 53a6420

Please sign in to comment.