Skip to content

Commit

Permalink
Merge branch 'main' into static-constexpr
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll authored Jan 18, 2022
2 parents e0b037c + 280c00b commit cb523e1
Show file tree
Hide file tree
Showing 68 changed files with 7,322 additions and 54 deletions.
4 changes: 4 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,10 @@ release will remove the deprecated code.
1. The out stream operator is guaranteed to return always plain 0 and not to
return -0, 0.0 or other instances of zero value.

## Ignition Math 6.9.2 to 6.10.0

1. **Color::HSV()**: A bug related to the hue output of this function was fixed.

## Ignition Math 6.8 to 6.9

1. **SphericalCoordinates**: A bug related to the LOCAL frame was fixed. To
Expand Down
6 changes: 6 additions & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,9 @@ find_package(ignition-math${IGN_MATH_VER} REQUIRED)
add_executable(angle_example angle_example.cc)
target_link_libraries(angle_example ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

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

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

Expand All @@ -33,6 +36,9 @@ target_link_libraries(quaternion_from_euler ignition-math${IGN_MATH_VER}::igniti
add_executable(quaternion_to_euler quaternion_to_euler.cc)
target_link_libraries(quaternion_to_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(temperature_example temperature_example.cc)
target_link_libraries(temperature_example ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER})

Expand Down
57 changes: 57 additions & 0 deletions examples/color_example.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
/*
* 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/Color.hh>

int main(int argc, char **argv)
{

//! [Create a color]
ignition::math::Color a = ignition::math::Color(0.3, 0.4, 0.5);
//! [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.ignition::math::Color::Set(0.6, 0.7, 0.8, 1.0);
//! [Set a new color value]
std::cout << "The RGBA value of a: " << a << std::endl;

//! [Set value from BGRA]
// 0xFF0000FF is blue in BGRA. Convert it to RGBA.
ignition::math::Color::BGRA blue = 0xFF0000FF;
a.ignition::math::Color::SetFromBGRA(blue);
//! [Set value from BGRA]

//! [Math operator]
std::cout << "Check if a is Blue: " << (a == ignition::math::Color::Blue) << std::endl;
std::cout << "The RGB value of a should be (0, 0, 1): " << a[0] << ", "
<< a[1] << ", "
<< a[2] << std::endl;
//! [Math operator]

//! [Set value from HSV]
// Initialize with HSV. (240, 1.0, 1.0) is blue in HSV.
a.ignition::math::Color::SetFromHSV(240.0, 1.0, 1.0);
std::cout << "The HSV value of a: " << a.HSV() << std::endl;
std::cout << "The RGBA value of a should be (0, 0, 1, 1): " << a << std::endl;
//! [Set value from HSV]

}
//! [complete]
8 changes: 4 additions & 4 deletions examples/quaternion_from_euler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ int main(int argc, char **argv)
if (argc != 4)
{
std::cerr << "Invalid usage\n\n"
<< "Usage (angles specified in radians):\n"
<< "Usage (angles specified in degrees):\n"
<< " quaternion_from_euler "
<< "<float_roll> <float_pitch> <float_yaw>\n\n"
<< "Example\n"
Expand All @@ -53,9 +53,9 @@ int main(int argc, char **argv)
return -1;
}

double roll = strToDouble(argv[1]);
double pitch = strToDouble(argv[2]);
double yaw = strToDouble(argv[3]);
double roll = IGN_DTOR(strToDouble(argv[1]));
double pitch = IGN_DTOR(strToDouble(argv[2]));
double yaw = IGN_DTOR(strToDouble(argv[3]));

std::cout << "Converting Euler angles:\n";
printf(" roll % .6f radians\n"
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
20 changes: 15 additions & 5 deletions include/ignition/math/AxisAlignedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,9 @@ namespace ignition
/// greater than zero.
/// \return Density of the cylinder in kg/m^3. A negative value is
/// returned if radius, length or _mass is <= 0.
public: double DensityFromMass(const double _mass) const;
/// \deprecated Unimplemented
public: double IGN_DEPRECATED(6.0) DensityFromMass(
const double _mass) const;

/// \brief Set the density of this box based on a mass value.
/// Density is computed using
Expand All @@ -243,15 +245,21 @@ namespace ignition
/// \return True if the density was set. False is returned if the
/// box's size or the _mass value are <= 0.
/// \sa double DensityFromMass(const double _mass) const
public: bool SetDensityFromMass(const double _mass);
/// \deprecated Unimplemented
public: bool IGN_DEPRECATED(6.0) SetDensityFromMass(
const double _mass);

/// \brief Get the material associated with this box.
/// \return The material assigned to this box.
public: const ignition::math::Material &Material() const;
/// \deprecated Unimplemented
public: const ignition::math::Material IGN_DEPRECATED(6.0)
&Material() const;

/// \brief Set the material associated with this box.
/// \param[in] _mat The material assigned to this box
public: void SetMaterial(const ignition::math::Material &_mat);
/// \deprecated Unimplemented
public: void IGN_DEPRECATED(6.0) SetMaterial(
const ignition::math::Material &_mat);

/// \brief Get the mass matrix for this box. This function
/// is only meaningful if the box's size and material
Expand All @@ -260,7 +268,9 @@ namespace ignition
/// here.
/// \return False if computation of the mass matrix failed, which
/// could be due to an invalid size (<=0) or density (<=0).
public: bool MassMatrix(MassMatrix3d &_massMat) const;
/// \deprecated Unimplemented
public: bool IGN_DEPRECATED(6.0) MassMatrix(
MassMatrix3d &_massMat) const;

/// \brief Clip a line to a dimension of the box.
/// This is a helper function to Intersects
Expand Down
24 changes: 24 additions & 0 deletions include/ignition/math/Color.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@ namespace ignition
/// \class Color Color.hh ignition/math/Color.hh
/// \brief Defines a color using a red (R), green (G), blue (B), and alpha
/// (A) component. Each color component is in the range [0..1].
///
/// ## Example
///
/// \snippet examples/color_example.cc complete
class IGNITION_MATH_VISIBLE Color
{
/// \brief (1, 1, 1)
Expand All @@ -56,18 +60,38 @@ namespace ignition

/// \typedef RGBA
/// \brief A RGBA packed value as an unsigned int
/// Each 8 bits corresponds to a channel.
///
/// \code
/// RGBA a = 0xFF0000FF; // (1, 0, 0, 1) for RGBA, i.e. red.
/// \endcode
public: typedef unsigned int RGBA;

/// \typedef BGRA
/// \brief A BGRA packed value as an unsigned int
/// Each 8 bits corresponds to a channel.
///
/// \code
/// BGRA a = 0xFF0000FF; // (0, 0, 1, 1) for RGBA, i.e. blue.
/// \endcode
public: typedef unsigned int BGRA;

/// \typedef ARGB
/// \brief A ARGB packed value as an unsigned int
/// Each 8 bits corresponds to a channel.
///
/// \code
/// ARGB a = 0xFF0000FF; // (0, 0, 1, 1) for RGBA, i.e. blue.
/// \endcode
public: typedef unsigned int ARGB;

/// \typedef ABGR
/// \brief A ABGR packed value as an unsigned int
/// Each 8 bits corresponds to a channel.
///
/// \code
/// ABGR a = 0xFF0000FF; // (1, 0, 0, 1) for RGBA, i.e. red.
/// \endcode
public: typedef unsigned int ABGR;

/// \brief Constructor
Expand Down
3 changes: 2 additions & 1 deletion include/ignition/math/Vector2.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define IGNITION_MATH_VECTOR2_HH_

#include <algorithm>
#include <cmath>
#include <istream>
#include <limits>
#include <ostream>
Expand Down Expand Up @@ -102,7 +103,7 @@ namespace ignition
/// \brief Normalize the vector length
public: void Normalize()
{
double d = this->Length();
T d = this->Length();

if (!equal<T>(d, static_cast<T>(0.0)))
{
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/math/Vector3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ namespace ignition
/// \return an orthogonal vector
public: Vector3 Perpendicular() const
{
static const T sqrZero = 1e-06 * 1e-06;
static const T sqrZero = static_cast<T>(1e-06 * 1e-06);

Vector3<T> perp = this->Cross(Vector3(1, 0, 0));

Expand Down
1 change: 1 addition & 0 deletions include/ignition/math/Vector4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define IGNITION_MATH_VECTOR4_HH_

#include <algorithm>
#include <cmath>
#include <limits>

#include <ignition/math/Matrix4.hh>
Expand Down
3 changes: 2 additions & 1 deletion src/Color.cc
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ Vector3f Color::HSV() const

if (equal(delta, 0.0f))
{
hsv.X() = -1;
hsv.X() = 0.0;
hsv.Y() = 0.0;
}
else if (equal(this->r, min))
Expand All @@ -152,6 +152,7 @@ Vector3f Color::HSV() const
else
hsv.X() = 1 - ((this->r - this->g) / delta);

hsv.X() *= 60.0;
return hsv;
}

Expand Down
Loading

0 comments on commit cb523e1

Please sign in to comment.