27 #ifndef _SR_MATH_UTILS_HPP_ 28 #define _SR_MATH_UTILS_HPP_ 30 #include <boost/random/mersenne_twister.hpp> 31 #include <boost/random/uniform_int.hpp> 32 #include <boost/random/uniform_real.hpp> 33 #include <boost/thread/detail/singleton.hpp> 41 static const double pi = 3.14159265;
50 static inline double to_rad(
double degrees)
52 return degrees * 0.017453292519943295;
64 return rad * 57.295779513082323;
67 static inline int ipow(
int base,
int exp)
85 if (bit_mask & (((int64_t) 1) << index))
113 uint16_t last_value = full_value & 0xFFFF;
114 full_value &= (uint64_t) 0xFFFFFFFFFFFF0000LL;
116 if (new_value < last_value)
118 full_value += (uint64_t) 0x0000000000010000LL;
121 full_value |= (uint64_t) new_value;
140 double x0,
double y0,
141 double x1,
double y1)
178 std::pair<double, double>
compute(
double q,
double timestamp)
194 if (
tau > 0.0 &&
dt > 0.0)
195 alpha = exp(-
dt /
tau);
225 xk_1(0.0), vk_1(0.0), xk(0.0), vk(0.0), rk(0.0),
240 std::pair<double, double>
compute(
double xm,
double timestamp)
244 xk = xk_1 + (vk_1 *
dt);
257 timestamp_1 = timestamp;
278 static inline int sign(
double x)
280 return x < 0.0 ? -1 : 1;
299 dist(
boost::uniform_real<>(0.0, 1.0))
311 T
generate(T min = static_cast<T> (0), T max = static_cast<T> (1))
313 return static_cast<T
> (
min + dist(
gen) * (max -
min));
334 typedef boost::detail::thread::singleton<class Random_>
Random;
static int sign(double x)
static uint64_t counter_with_overflow(uint64_t full_value, uint16_t new_value)
TFSIMD_FORCE_INLINE const tfScalar & y() const
static double to_degrees(double rad)
T generate(T min=static_cast< T >(0), T max=static_cast< T >(1))
std::pair< double, double > value_derivative
static int ipow(int base, int exp)
static double to_rad(double degrees)
std::pair< double, double > compute(double xm, double timestamp)
std::pair< double, double > value_derivative
static double linear_interpolate_(double x, double x0, double y0, double x1, double y1)
LowPassFilter(double tau=0.05)
boost::detail::thread::singleton< class Random_ > Random
AlphaBetaFilter(double alpha=0.85, double beta=0.05)
static bool is_bit_mask_index_true(int64_t bit_mask, int index)
static bool is_bit_mask_index_false(int64_t bit_mask, int index)
std::pair< double, double > compute(double q, double timestamp)