Skip to content

Commit

Permalink
mathlib Limits don't use references
Browse files Browse the repository at this point in the history
 - cleanup Limits.hpp
 - add -Waddress-of-packed-member where available
 - fixes #11408
  • Loading branch information
dagar committed Feb 8, 2019
1 parent ab6ab97 commit 0d546df
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 23 deletions.
9 changes: 8 additions & 1 deletion cmake/px4_add_common_flags.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,8 @@ function(px4_add_common_flags)
-Wunknown-pragmas
-Wunused-variable

#-Wcast-align # TODO: fix and enable

# disabled warnings
-Wno-implicit-fallthrough # set appropriate level and update
-Wno-missing-field-initializers
Expand All @@ -97,7 +99,8 @@ function(px4_add_common_flags)
add_compile_options(
-Qunused-arguments

-Wno-address-of-packed-member
-Waddress-of-packed-member

-Wno-unknown-warning-option
-Wno-unused-const-variable
-Wno-varargs
Expand All @@ -111,6 +114,10 @@ function(px4_add_common_flags)
add_compile_options(-fdiagnostics-color=always)
endif()

if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 9)
add_compile_options(-Waddress-of-packed-member)
endif()

add_compile_options(
-fno-builtin-printf
-fno-strength-reduce
Expand Down
33 changes: 11 additions & 22 deletions src/lib/mathlib/math/Limits.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,71 +47,60 @@
#define MATH_PI 3.141592653589793238462643383280
#endif

//this should be defined in stdint.h, but seems to be missing in the ARM toolchain (5.2.0)
#ifndef UINT64_C
# if __WORDSIZE == 64
# define UINT64_C(c) c ## UL
# else
# define UINT64_C(c) c ## ULL
# endif
#endif


namespace math
{

template<typename _Tp>
constexpr const _Tp &min(const _Tp &a, const _Tp &b)
constexpr _Tp min(_Tp a, _Tp b)
{
return (a < b) ? a : b;
}

template<typename _Tp>
constexpr const _Tp &max(const _Tp &a, const _Tp &b)
constexpr _Tp max(_Tp a, _Tp b)
{
return (a > b) ? a : b;
}

template<typename _Tp>
constexpr const _Tp &constrain(const _Tp &val, const _Tp &min_val, const _Tp &max_val)
constexpr _Tp constrain(_Tp val, _Tp min_val, _Tp max_val)
{
return (val < min_val) ? min_val : ((val > max_val) ? max_val : val);
}

/** Constrain float values to valid values for int16_t.
* Invalid values are just clipped to be in the range for int16_t. */
inline int16_t constrainFloatToInt16(float value)
constexpr int16_t constrainFloatToInt16(float value)
{
return (int16_t)math::constrain(value, (float)INT16_MIN, (float)INT16_MAX);
}


template<typename _Tp>
inline constexpr bool isInRange(const _Tp &val, const _Tp &min_val, const _Tp &max_val)
constexpr bool isInRange(_Tp val, _Tp min_val, _Tp max_val)
{
return (min_val <= val) && (val <= max_val);
}

template<typename T>
constexpr T radians(const T degrees)
constexpr T radians(T degrees)
{
return degrees * (static_cast<T>(MATH_PI) / static_cast<T>(180));
}

template<typename T>
constexpr T degrees(const T radians)
constexpr T degrees(T radians)
{
return radians * (static_cast<T>(180) / static_cast<T>(MATH_PI));
}

/** Save way to check if float is zero */
inline bool isZero(const float val)
/** Safe way to check if float is zero */
inline bool isZero(float val)
{
return fabsf(val - 0.0f) < FLT_EPSILON;
}

/** Save way to check if double is zero */
inline bool isZero(const double val)
/** Safe way to check if double is zero */
inline bool isZero(double val)
{
return fabs(val - 0.0) < DBL_EPSILON;
}
Expand Down

0 comments on commit 0d546df

Please sign in to comment.