mathlib Limits constexpr helpers don't use references (#11411)

- fixes #11408
 - cleanup Limits.hpp
This commit is contained in:
Daniel Agar 2019-02-08 14:10:09 -05:00 committed by GitHub
parent 13634e6757
commit 2217faf812
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 18 additions and 23 deletions

View File

@ -79,6 +79,8 @@ function(px4_add_common_flags)
-Wunknown-pragmas -Wunknown-pragmas
-Wunused-variable -Wunused-variable
#-Wcast-align # TODO: fix and enable
# disabled warnings # disabled warnings
-Wno-implicit-fallthrough # set appropriate level and update -Wno-implicit-fallthrough # set appropriate level and update
-Wno-missing-field-initializers -Wno-missing-field-initializers
@ -97,7 +99,7 @@ function(px4_add_common_flags)
add_compile_options( add_compile_options(
-Qunused-arguments -Qunused-arguments
-Wno-address-of-packed-member -Wno-address-of-packed-member # TODO: fix and enable (mavlink, etc)
-Wno-unknown-warning-option -Wno-unknown-warning-option
-Wno-unused-const-variable -Wno-unused-const-variable
-Wno-varargs -Wno-varargs
@ -111,6 +113,10 @@ function(px4_add_common_flags)
add_compile_options(-fdiagnostics-color=always) add_compile_options(-fdiagnostics-color=always)
endif() endif()
if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 9)
add_compile_options(-Wno-address-of-packed-member) # TODO: fix and enable (mavlink, etc)
endif()
add_compile_options( add_compile_options(
-fno-builtin-printf -fno-builtin-printf
-fno-strength-reduce -fno-strength-reduce

View File

@ -47,71 +47,60 @@
#define MATH_PI 3.141592653589793238462643383280 #define MATH_PI 3.141592653589793238462643383280
#endif #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 namespace math
{ {
template<typename _Tp> 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; return (a < b) ? a : b;
} }
template<typename _Tp> 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; return (a > b) ? a : b;
} }
template<typename _Tp> 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); return (val < min_val) ? min_val : ((val > max_val) ? max_val : val);
} }
/** Constrain float values to valid values for int16_t. /** Constrain float values to valid values for int16_t.
* Invalid values are just clipped to be in the range 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); return (int16_t)math::constrain(value, (float)INT16_MIN, (float)INT16_MAX);
} }
template<typename _Tp> 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); return (min_val <= val) && (val <= max_val);
} }
template<typename T> 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)); return degrees * (static_cast<T>(MATH_PI) / static_cast<T>(180));
} }
template<typename T> 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)); return radians * (static_cast<T>(180) / static_cast<T>(MATH_PI));
} }
/** Save way to check if float is zero */ /** Safe way to check if float is zero */
inline bool isZero(const float val) inline bool isZero(float val)
{ {
return fabsf(val - 0.0f) < FLT_EPSILON; return fabsf(val - 0.0f) < FLT_EPSILON;
} }
/** Save way to check if double is zero */ /** Safe way to check if double is zero */
inline bool isZero(const double val) inline bool isZero(double val)
{ {
return fabs(val - 0.0) < DBL_EPSILON; return fabs(val - 0.0) < DBL_EPSILON;
} }