Skip to content

Commit

Permalink
Merge branch 'ahcorde/python/triangle' of https://github.com/ignition…
Browse files Browse the repository at this point in the history
…robotics/ign-math into ahcorde/python/triangle
  • Loading branch information
ahcorde committed Oct 8, 2021
2 parents 093a8a2 + 7d3cbf7 commit 80baf10
Show file tree
Hide file tree
Showing 12 changed files with 283 additions and 11 deletions.
4 changes: 2 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.9.0)
project(ignition-math6 VERSION 6.9.1)

#============================================================================
# Find ignition-cmake
Expand All @@ -15,7 +15,7 @@ find_package(ignition-cmake2 2.8.0 REQUIRED)
# Configure the project
#============================================================================
set (c++standard 17)
ign_configure_project(VERSION_SUFFIX pre1)
ign_configure_project(VERSION_SUFFIX)

#============================================================================
# Set project-specific options
Expand Down
12 changes: 11 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,15 @@

## Ignition Math 6.x.x

## Ignition Math 6.9.0 (2021-09-XX)
## 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)
Expand Down Expand Up @@ -64,6 +72,8 @@
* [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)

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
4 changes: 0 additions & 4 deletions include/ignition/math/Cylinder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -100,10 +100,6 @@ namespace ignition
public: void SetRotationalOffset(
const Quaternion<Precision> &_rotOffset);

/// \brief Set the length in meters.
/// \param[in] _length The length of the cylinder in meters.
public: void SetLength(const Precision _length) const;

/// \brief Get the material associated with this cylinder.
/// \return The material assigned to this cylinder
public: const Material &Mat() const;
Expand Down
1 change: 1 addition & 0 deletions src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,7 @@ if (PYTHONLIBS_FOUND)
Kmeans_TEST
Line2_TEST
Line3_TEST
Material_TEST
Matrix3_TEST
Matrix4_TEST
MovingWindowFilter_TEST
Expand Down
2 changes: 1 addition & 1 deletion src/python/Color_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,7 @@ def test_const_set(self):

def test_stream_out(self):
c = Color(0.1, 0.2, 0.3, 0.5)
self.assertAlmostEqual(str(c), "0.1 0.2 0.3 0.5")
self.assertEqual(str(c), "0.1 0.2 0.3 0.5")

def test_HSV(self):
clr = Color()
Expand Down
59 changes: 59 additions & 0 deletions src/python/Material.i
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
/*
* 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.
*
*/

%module material
%{
#include <ignition/math/config.hh>
#include <ignition/math/Export.hh>
#include <ignition/math/Material.hh>
#include <ignition/math/MaterialType.hh>
%}

%include "std_string.i"
%include "std_map.i"

%template(map_material_type) std::map<int,
ignition::math::Material>;

namespace ignition
{
namespace math
{
class Material
{
%rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) "";
public: Material();
public: explicit Material(const MaterialType _type);
public: explicit Material(const std::string &_typename);
public: explicit Material(const double _density);
public: Material(const Material &_material);
public: ~Material();
public: static const std::map<int, Material> &Predefined();
public: void SetToNearestDensity(
const double _value,
const double _epsilon = std::numeric_limits<double>::max());
public: bool operator==(const Material &_material) const;
public: bool operator!=(const Material &_material) const;
public: MaterialType Type() const;
public: void SetType(const MaterialType _type);
public: std::string Name() const;
public: void SetName(const std::string &_name);
public: double Density() const;
public: void SetDensity(const double _density);
};
}
}
47 changes: 47 additions & 0 deletions src/python/MaterialType.i
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
/*
* 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.
*
*/

%module materialtype
%{
#include <ignition/math/config.hh>
#include <ignition/math/Export.hh>
#include <ignition/math/MaterialType.hh>
%}

namespace ignition
{
namespace math
{
enum class MaterialType
{
STYROFOAM = 0,
PINE,
WOOD,
OAK,
PLASTIC,
CONCRETE,
ALUMINUM,
STEEL_ALLOY,
STEEL_STAINLESS,
IRON,
BRASS,
COPPER,
TUNGSTEN,
UNKNOWN_MATERIAL
};
}
}
110 changes: 110 additions & 0 deletions src/python/Material_TEST.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
# 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.

import sys
import unittest

import ignition.math


class TestMaterial(unittest.TestCase):

def test_init(self):
mats = ignition.math.Material.predefined()
self.assertTrue(len(mats))

# Make sure that the number of elements in the MaterialType enum matches
# the number of elements in the MaterialDensity::materials map.
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL, len(mats))

# Iterate over each element in the enum. Check the that enum value
# matches the type value in the mats map.
for i in range(ignition.math.MaterialType_UNKNOWN_MATERIAL):
# Get the type of the material for MaterialType i.
self.assertEqual(i, next(iter(mats.find(i)))[1].type())

# The name should not be empty
self.assertTrue(next(iter(mats.find(i)))[1].name())

# The density should be less than the max double value and greater than
# zero.
self.assertLess(next(iter(mats.find(i)))[1].density(), sys.float_info.max)
self.assertGreater(next(iter(mats.find(i)))[1].density(), 0.0)

malicious = ignition.math.Material(42)
self.assertEqual(-1.0, malicious.density())
self.assertEqual('', malicious.name())

byDensity = ignition.math.Material(42.2)
self.assertEqual(42.2, byDensity.density())
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL, byDensity.type())

def test_comparison(self):
aluminum = ignition.math.Material(ignition.math.MaterialType_ALUMINUM)

modified = ignition.math.Material(aluminum)
self.assertEqual(modified, aluminum)

modified.set_density(1234.0)
self.assertNotEqual(modified, aluminum)

modified = ignition.math.Material(aluminum)
self.assertEqual(modified, aluminum)

modified.set_type(ignition.math.MaterialType_PINE)
self.assertNotEqual(modified, aluminum)

def test_accessors(self):

mat = ignition.math.Material("Aluminum")
mat1 = ignition.math.Material("aluminum")
mat2 = ignition.math.Material(ignition.math.MaterialType_ALUMINUM)
mat3 = ignition.math.Material(mat2)

self.assertAlmostEqual(2700.0, mat.density())
self.assertEqual(mat, mat1)
self.assertEqual(mat1, mat2)
self.assertEqual(mat2, mat3)

# Test constructor
mat4 = ignition.math.Material(mat3)
self.assertEqual(mat2, mat4)

mat5 = ignition.math.Material(mat4)
self.assertEqual(mat2, mat5)

mat = ignition.math.Material("Notfoundium")
self.assertGreater(0.0, mat.density())
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL,
mat.type())
self.assertFalse(mat.name())

material = ignition.math.Material()
material.set_to_nearest_density(19300.0)
self.assertEqual(ignition.math.MaterialType_TUNGSTEN, material.type())
self.assertAlmostEqual(19300.0, material.density())

material = ignition.math.Material()
material.set_to_nearest_density(1001001.001, 1e-3)
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL,
material.type())
self.assertGreater(0.0, material.density())
material = ignition.math.Material()
material.set_to_nearest_density(1001001.001)
self.assertEqual(ignition.math.MaterialType_TUNGSTEN, material.type())
self.assertAlmostEqual(19300, material.density())


if __name__ == '__main__':
unittest.main()
4 changes: 2 additions & 2 deletions src/python/Pose3_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -141,8 +141,8 @@ def test_pose_atributes(self):
self.assertTrue(pose.rot() == Quaterniond(1, 0, 0))

def test_stream_out(self):
p = Pose3d(0.1, 1.2, 2.3, 0.0, 0.1, 1.0)
self.assertAlmostEqual(str(p), "0.1 1.2 2.3 0 0.1 1")
p = Pose3d(0.1, 1.2, 2.3, 0.01, 0.1, 1.0)
self.assertEqual(str(p), "0.1 1.2 2.3 0.01 0.1 1")

def test_mutable_pose(self):
pose = Pose3d(0, 1, 2, 0, 0, 0)
Expand Down
2 changes: 2 additions & 0 deletions src/python/python.i
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
%include SignalStats.i
%include Spline.i
%include Temperature.i
%include MaterialType.i
%include Material.i
%include Triangle.i
%include Triangle3.i
%include Kmeans.i
Expand Down
47 changes: 46 additions & 1 deletion tutorials/installation.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,22 @@ sudo apt install libignition-math<#>-dev
Be sure to replace `<#>` with a number value, such as 1 or 2, depending on
which version you need.

### macOS

On macOS, add OSRF packages:
```
ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)"
brew tap osrf/simulation
```

Install Ignition Math:
```
brew install ignition-math<#>
```

Be sure to replace `<#>` with a number value, such as 1 or 2, depending on
which version you need.

## Windows

Install [Conda package management system](https://docs.conda.io/projects/conda/en/latest/user-guide/install/download.html).
Expand Down Expand Up @@ -126,6 +142,36 @@ The optional Eigen component of Ignition Math requires:
sudo make install
```

### macOS

1. Clone the repository
```
git clone https://github.com/ignitionrobotics/ign-math -b ign-math<#>
```
Be sure to replace `<#>` with a number value, such as 1 or 2, depending on
which version you need.

2. Install dependencies
```
brew install --only-dependencies ignition-math<#>
```
Be sure to replace `<#>` with a number value, such as 1 or 2, depending on
which version you need.

3. Configure and build
```
cd ign-math
mkdir build
cd build
cmake ..
make
```

4. Optionally, install
```
sudo make install
```

### Windows

1. Navigate to `condabin` if necessary to use the `conda` command (i.e., if Conda is not in your `PATH` environment variable. You can find the location of `condabin` in Anaconda Prompt, `where conda`).
Expand Down Expand Up @@ -229,4 +275,3 @@ The interfaces and Ruby test codes are in the `src` folder. To use a C++ class i
```
ctest -R Ruby_TEST.rb
```

0 comments on commit 80baf10

Please sign in to comment.