Skip to content

Commit

Permalink
merged from ign-math6
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Dec 23, 2021
2 parents 27e8206 + be461ca commit aeefd4c
Show file tree
Hide file tree
Showing 22 changed files with 965 additions and 19 deletions.
3 changes: 3 additions & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,9 @@ target_link_libraries(quaternion_to_euler ignition-math${IGN_MATH_VER}::ignition
add_executable(quaternion_from_euler quaternion_from_euler.cc)
target_link_libraries(quaternion_from_euler ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

add_executable(rand_example rand_example.cc)
target_link_libraries(rand_example ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

add_executable(graph_example graph_example.cc)
target_link_libraries(graph_example ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

Expand Down
54 changes: 54 additions & 0 deletions examples/rand_example.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
/*
* 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.
*
*/
//! [complete]
#include <iostream>
#include <ignition/math/Rand.hh>

// You can plot the data generated by this program by following these
// steps.
//
// 1. Run this program and save the output to a file:
// ./rand_example normal > normal.data
// ./rand_example uniform > uniform.data
//
// 2. Use gnuplot to create a plot:
// gnuplot -c rand_view_normal.gp > normal.jpg
// gnuplot -c rand_view_uniform.gp > uniform.jpg
int main(int argc, char **argv)
{
if (argc < 2)
{
std::cout << "./rand_example [normal, uniform]" << '\n';
return -1;
}
for (int i = 0; i < 100000; ++i)
{
double value;
if (std::string(argv[1]) == "normal")
{
value = ignition::math::Rand::DblNormal(0, 100);
}
else if (std::string(argv[1]) == "uniform")
{
value = ignition::math::Rand::DblUniform(0, 1000);
}
std::cout << value << std::endl;
}

return 0;
}
//! [complete]
37 changes: 37 additions & 0 deletions examples/rand_example.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
# 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.

# You can plot the data generated by this program by following these
# steps.
#
# 1. Run this program and save the output to a file:
# ./rand_example normal > normal.data
# ./rand_example uniform > uniform.data
#
# 2. Use gnuplot to create a plot:
# gnuplot -c rand_view_normal.gp > normal.jpg
# gnuplot -c rand_view_uniform.gp > uniform.jpg
from ignition.math import Rand
import sys

if (len(sys.argv) < 2):
print("python rand_example [normal, uniform]")
else:
for i in range(100000):
value = 0
if (sys.argv[1] == "uniform"):
value = Rand.dbl_uniform(0, 1000);
elif (sys.argv[1] == "normal"):
value = Rand.dbl_normal(0, 100);
print(value)
12 changes: 12 additions & 0 deletions examples/rand_view_normal.gp
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
set terminal jpeg
binwidth = 5
bin(x,width)=width*floor(x/width)

set tics out nomirror
set style fill transparent solid 0.5 border lt -1
set xrange [-1000:1000]
set xtics binwidth
set boxwidth binwidth
set yrange [0:2500]

plot "normal.data" u (bin($1,binwidth)):(1.0) smooth freq with boxes notitle
12 changes: 12 additions & 0 deletions examples/rand_view_uniform.gp
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
set terminal jpeg
binwidth = 50
bin(x,width)=width*floor(x/width)

set tics out nomirror
set style fill transparent solid 0.5 border lt -1
set xrange [0:1000]
set xtics binwidth
set boxwidth binwidth
set yrange [0:10000]

plot "uniform.data" u (bin($1,binwidth)):(1.0) smooth freq with boxes notitle
5 changes: 0 additions & 5 deletions src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -89,16 +89,13 @@ if (PYTHONLIBS_FOUND)
set(python_tests
AxisAlignedBox_TEST
Box_TEST
Color_TEST
Cylinder_TEST
DiffDriveOdometry_TEST
Filter_TEST
Frustum_TEST
GaussMarkovProcess_TEST
Helpers_TEST
Inertial_TEST
Kmeans_TEST
Line2_TEST
Line3_TEST
MassMatrix3_TEST
Material_TEST
Expand All @@ -111,8 +108,6 @@ if (PYTHONLIBS_FOUND)
Pose3_TEST
python_TEST
Quaternion_TEST
Rand_TEST
RollingMean_TEST
RotationSpline_TEST
SemanticVersion_TEST
SignalStats_TEST
Expand Down
9 changes: 9 additions & 0 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@ if (${pybind11_FOUND})
pybind11_add_module(math SHARED
src/_ignition_math_pybind11.cc
src/Angle.cc
src/Color.cc
src/Helpers.cc
src/Rand.cc
src/RollingMean.cc
src/StopWatch.cc
)

Expand Down Expand Up @@ -69,6 +73,11 @@ if (${pybind11_FOUND})
# Add the Python tests
set(python_tests
Angle_TEST
Color_TEST
Helpers_TEST
Line2_TEST
Rand_TEST
RollingMean_TEST
StopWatch_TEST
Vector2_TEST
Vector3_TEST
Expand Down
154 changes: 154 additions & 0 deletions src/python_pybind11/src/Color.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,154 @@
/*
* 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.
*
*/

#include <string>

#include "Color.hh"
#include <ignition/math/Color.hh>

#include <pybind11/operators.h>

using namespace pybind11::literals;

namespace ignition
{
namespace math
{
namespace python
{
void defineMathColor(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Color;
auto toString = [](const Class &si) {
std::stringstream stream;
stream << si;
return stream.str();
};
std::string pyclass_name = typestr;
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def(py::init<const Class&>())
.def(py::init<const float, const float, const float, const float>(),
py::arg("_r") = 0.0, py::arg("_g") = 0.0,
py::arg("_b") = 0.0, py::arg("_a") = 1.0f)
.def(py::self + py::self)
.def(py::self += py::self)
.def(py::self + float())
.def(py::self - py::self)
.def(py::self -= py::self)
.def(py::self - float())
.def(py::self / py::self)
.def(py::self /= py::self)
.def(py::self / float())
.def(py::self * py::self)
.def(py::self *= py::self)
.def(py::self * float())
.def(py::self != py::self)
.def(py::self == py::self)
.def_readonly_static("WHITE", &Class::White, "(1, 1, 1)")
.def_readonly_static("BLACK", &Class::Black, "(0, 0, 0)")
.def_readonly_static("RED", &Class::Red, "(1, 0, 0)")
.def_readonly_static("GREEN", &Class::Green, "(0, 1, 0)")
.def_readonly_static("BLUE", &Class::Blue, "(0, 0, 1)")
.def_readonly_static("YELLOW", &Class::Yellow, "(1, 1, 0)")
.def_readonly_static("MAGENTA", &Class::Magenta, "(1, 0, 1)")
.def_readonly_static("CYAN", &Class::Cyan, "(0, 1, 1)")
.def("reset",
&Class::Reset,
"Reset the color to default values to red=0, green=0, blue=0, alpha=1")
.def("set",
&Class::Set,
py::arg("_r") = 1.0, py::arg("_g") = 1.0,
py::arg("_b") = 1.0, py::arg("_a") = 1.0,
"Set the contents of the vector")
.def("hsv",
&Class::HSV,
"Set the color in HSV colorspace")
.def("set_from_hsv",
&Class::SetFromHSV,
"Set a color based on HSV values")
.def("yuv",
&Class::YUV,
"Get the color in YUV colorspace")
.def("set_from_yuv",
&Class::SetFromYUV,
"Set from yuv")
.def("as_rgba",
&Class::AsRGBA,
"Get as uint32 RGBA packed value")
.def("as_bgra",
&Class::AsBGRA,
"Get as uint32 BGRA packed value")
.def("as_argb",
&Class::AsARGB,
"Get as uint32 ARGB packed value")
.def("as_abgr",
&Class::AsABGR,
"Get as uint32 ABGR packed value")
.def("set_from_rgba",
&Class::SetFromRGBA,
"Set from uint32 RGBA packed value")
.def("set_from_bgra",
&Class::SetFromBGRA,
"Set from uint32 BGRA packed value")
.def("set_from_argb",
&Class::SetFromARGB,
"Set from uint32 ARGB packed value")
.def("set_from_abgr",
&Class::SetFromABGR,
"Set from uint32 ABGR packed value")
.def("r",
py::overload_cast<>(&Class::R),
"Get the red value")
.def("g",
py::overload_cast<>(&Class::G),
"Get the green value")
.def("b",
py::overload_cast<>(&Class::B),
"Get the blue value")
.def("a",
py::overload_cast<>(&Class::A),
"Get the alpha value")
.def("r",
py::overload_cast<float>(&Class::R),
"Get the red value")
.def("g",
py::overload_cast<float>(&Class::G),
"Get the green value")
.def("b",
py::overload_cast<float>(&Class::B),
"Get the blue value")
.def("a",
py::overload_cast<float>(&Class::A),
"Get the alpha value")
.def("__str__", toString)
.def("__repr__", toString)
.def("__copy__", [](const Class &self) {
return Class(self);
})
.def("__deepcopy__", [](const Class &self, py::dict) {
return Class(self);
}, "memo"_a)
.def("__getitem__",
(&Class::operator[]));
}
} // namespace python
} // namespace math
} // namespace ignition
42 changes: 42 additions & 0 deletions src/python_pybind11/src/Color.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
/*
* 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_PYTHON__COLOR_HH_
#define IGNITION_MATH_PYTHON__COLOR_HH_

#include <pybind11/pybind11.h>
#include <string>

namespace py = pybind11;

namespace ignition
{
namespace math
{
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Color
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathColor(py::module &m, const std::string &typestr);
} // namespace python
} // namespace math
} // namespace ignition

#endif // IGNITION_MATH_PYTHON__COLOR_HH_
Loading

0 comments on commit aeefd4c

Please sign in to comment.