2016-02-25 13:13:02 -04:00
|
|
|
#pragma once
|
2010-09-08 05:21:46 -03:00
|
|
|
|
2016-02-25 13:13:02 -04:00
|
|
|
#include "definitions.h"
|
2012-03-09 22:44:36 -04:00
|
|
|
|
2016-02-25 13:13:02 -04:00
|
|
|
#include <limits>
|
|
|
|
#include <type_traits>
|
2010-09-08 05:21:46 -03:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2016-03-31 18:43:36 -03:00
|
|
|
#include <cmath>
|
2011-12-15 22:47:07 -04:00
|
|
|
#include <stdint.h>
|
2016-02-25 13:13:02 -04:00
|
|
|
|
2012-03-09 22:44:36 -04:00
|
|
|
#include "rotations.h"
|
2010-09-08 05:21:46 -03:00
|
|
|
#include "vector2.h"
|
|
|
|
#include "vector3.h"
|
|
|
|
#include "matrix3.h"
|
2012-03-04 23:31:47 -04:00
|
|
|
#include "quaternion.h"
|
2011-12-14 23:34:58 -04:00
|
|
|
#include "polygon.h"
|
2014-04-03 19:44:56 -03:00
|
|
|
#include "edc.h"
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Param/AP_Param.h>
|
2016-02-25 08:07:27 -04:00
|
|
|
#include "location.h"
|
2012-02-17 19:00:26 -04:00
|
|
|
|
2014-04-03 19:44:56 -03:00
|
|
|
|
2012-02-17 19:00:26 -04:00
|
|
|
// define AP_Param types AP_Vector3f and Ap_Matrix3f
|
|
|
|
AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F);
|
2012-02-23 07:56:40 -04:00
|
|
|
|
2015-05-04 23:29:05 -03:00
|
|
|
// are two floats equal
|
|
|
|
static inline bool is_equal(const float fVal1, const float fVal2) { return fabsf(fVal1 - fVal2) < FLT_EPSILON ? true : false; }
|
2015-04-28 03:06:13 -03:00
|
|
|
|
2015-05-04 23:29:05 -03:00
|
|
|
// is a float is zero
|
|
|
|
static inline bool is_zero(const float fVal1) { return fabsf(fVal1) < FLT_EPSILON ? true : false; }
|
2015-04-28 02:36:53 -03:00
|
|
|
|
2012-02-23 07:56:40 -04:00
|
|
|
// a varient of asin() that always gives a valid answer.
|
2012-08-17 03:20:14 -03:00
|
|
|
float safe_asin(float v);
|
2012-02-23 19:40:56 -04:00
|
|
|
|
|
|
|
// a varient of sqrt() that always gives a valid answer.
|
2012-08-17 03:20:14 -03:00
|
|
|
float safe_sqrt(float v);
|
2012-02-23 20:23:12 -04:00
|
|
|
|
2015-12-05 05:10:07 -04:00
|
|
|
// return determinant of square matrix
|
|
|
|
float detnxn(const float C[], const uint8_t n);
|
|
|
|
|
|
|
|
// Output inverted nxn matrix when returns true, otherwise matrix is Singular
|
|
|
|
bool inversenxn(const float x[], float y[], const uint8_t n);
|
|
|
|
|
|
|
|
// invOut is an inverted 4x4 matrix when returns true, otherwise matrix is Singular
|
|
|
|
bool inverse3x3(float m[], float invOut[]);
|
|
|
|
|
|
|
|
// invOut is an inverted 3x3 matrix when returns true, otherwise matrix is Singular
|
|
|
|
bool inverse4x4(float m[],float invOut[]);
|
|
|
|
|
2015-12-28 19:19:05 -04:00
|
|
|
// matrix multiplication of two NxN matrices
|
|
|
|
float* mat_mul(float *A, float *B, uint8_t n);
|
|
|
|
|
2013-03-28 23:13:37 -03:00
|
|
|
/*
|
2016-04-27 06:35:18 -03:00
|
|
|
* Constrain an angle to be within the range: -180 to 180 degrees. The second
|
|
|
|
* parameter changes the units. Default: 1 == degrees, 10 == dezi,
|
|
|
|
* 100 == centi.
|
2013-03-28 23:13:37 -03:00
|
|
|
*/
|
2016-04-27 06:35:18 -03:00
|
|
|
template <class T>
|
|
|
|
float wrap_180(const T angle, float unit_mod = 1);
|
2013-03-28 23:13:37 -03:00
|
|
|
|
2013-06-01 05:18:50 -03:00
|
|
|
/*
|
2016-04-27 06:35:18 -03:00
|
|
|
* Wrap an angle in centi-degrees. See wrap_180().
|
2013-06-01 05:18:50 -03:00
|
|
|
*/
|
2016-04-27 06:35:18 -03:00
|
|
|
template <class T>
|
|
|
|
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f));
|
2013-06-01 05:18:50 -03:00
|
|
|
|
2015-11-24 17:11:34 -04:00
|
|
|
/*
|
2016-04-27 06:35:18 -03:00
|
|
|
* Constrain an euler angle to be within the range: 0 to 360 degrees. The
|
|
|
|
* second parameter changes the units. Default: 1 == degrees, 10 == dezi,
|
|
|
|
* 100 == centi.
|
2015-11-24 17:11:34 -04:00
|
|
|
*/
|
2016-04-27 06:35:18 -03:00
|
|
|
template <class T>
|
|
|
|
float wrap_360(const T angle, float unit_mod = 1);
|
|
|
|
|
|
|
|
/*
|
|
|
|
* Wrap an angle in centi-degrees. See wrap_360().
|
|
|
|
*/
|
|
|
|
template <class T>
|
|
|
|
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f));
|
|
|
|
|
|
|
|
/*
|
|
|
|
wrap an angle in radians to -PI ~ PI (equivalent to +- 180 degrees)
|
|
|
|
*/
|
|
|
|
template <class T>
|
|
|
|
float wrap_PI(const T radian);
|
|
|
|
|
|
|
|
/*
|
|
|
|
* wrap an angle in radians to 0..2PI
|
|
|
|
*/
|
|
|
|
template <class T>
|
|
|
|
float wrap_2PI(const T radian);
|
2015-11-24 17:11:34 -04:00
|
|
|
|
2016-04-16 06:58:58 -03:00
|
|
|
/*
|
|
|
|
* Constrain a value to be within the range: low and high
|
|
|
|
*/
|
|
|
|
template <class T>
|
|
|
|
T constrain_value(const T amt, const T low, const T high);
|
2016-04-27 06:35:18 -03:00
|
|
|
|
2016-04-16 06:58:58 -03:00
|
|
|
auto const constrain_float = &constrain_value<float>;
|
|
|
|
auto const constrain_int16 = &constrain_value<int16_t>;
|
|
|
|
auto const constrain_int32 = &constrain_value<int32_t>;
|
2015-03-21 05:48:46 -03:00
|
|
|
|
2012-12-18 22:33:52 -04:00
|
|
|
|
2015-05-29 04:04:29 -03:00
|
|
|
//matrix algebra
|
|
|
|
bool inverse(float x[], float y[], uint16_t dim);
|
|
|
|
|
2012-12-18 22:33:52 -04:00
|
|
|
// degrees -> radians
|
2015-03-21 05:48:46 -03:00
|
|
|
static inline float radians(float deg) {
|
|
|
|
return deg * DEG_TO_RAD;
|
|
|
|
}
|
2012-12-18 22:33:52 -04:00
|
|
|
|
|
|
|
// radians -> degrees
|
2015-03-21 05:48:46 -03:00
|
|
|
static inline float degrees(float rad) {
|
|
|
|
return rad * RAD_TO_DEG;
|
|
|
|
}
|
2012-12-18 22:33:52 -04:00
|
|
|
|
2016-04-16 06:58:46 -03:00
|
|
|
template<class T>
|
|
|
|
float sq(const T val)
|
|
|
|
{
|
|
|
|
return powf(static_cast<float>(val), 2);
|
2015-03-21 05:48:46 -03:00
|
|
|
}
|
|
|
|
|
2016-04-16 06:58:46 -03:00
|
|
|
/*
|
|
|
|
* Variadic template for calculating the square norm of a vector of any
|
|
|
|
* dimension.
|
|
|
|
*/
|
|
|
|
template<class T, class... Params>
|
|
|
|
float sq(const T first, const Params... parameters)
|
|
|
|
{
|
|
|
|
return sq(first) + sq(parameters...);
|
2015-03-21 05:48:46 -03:00
|
|
|
}
|
2012-12-18 22:33:52 -04:00
|
|
|
|
2016-04-16 06:58:46 -03:00
|
|
|
/*
|
|
|
|
* Variadic template for calculating the norm (pythagoras) of a vector of any
|
|
|
|
* dimension.
|
|
|
|
*/
|
|
|
|
template<class T, class... Params>
|
|
|
|
float norm(const T first, const Params... parameters)
|
|
|
|
{
|
|
|
|
return sqrt(static_cast<float>(sq(first, parameters...)));
|
2015-03-21 05:48:46 -03:00
|
|
|
}
|
2012-12-18 22:33:52 -04:00
|
|
|
|
AP_Math: turn MIN/MAX macros into inline functions
The problem with the current MIN/MAX macros is that they evaluate twice
the arguments. For example, these cases provide unintended results:
// a is incremented twice
a = MIN(a++, b);
// foo() with side-effects
a = MIN(foo(), b);
The alternative implementation here was provided by Daniel Frenzel using
template function. It doesn't have type safety as std::min and std::max,
but adding type safety would mean to check case by case what would be a
reasonable type and add proper casts. Here the arguments for MIN and MAX
can have different types and the return type is deduced from the
expression in the function.
Inspecting the current callers no place was found with the unintended
results above, but some in which now we don't calculate twice the
parameters will benefit from this new version. Examples:
float velocity_max = MIN(_pos_control.get_speed_xy(), safe_sqrt(0.5f*_pos_control.get_accel_xy()*_radius));
float acro_level_mix = constrain_float(1-MAX(MAX(abs(roll_in), abs(pitch_in)), abs(yaw_in))/4500.0, 0, 1)*ahrs.cos_pitch()
accel_x_cmss = (GRAVITY_MSS * 100) * (-(_ahrs.cos_yaw() * _ahrs.sin_pitch() / MAX(_ahrs.cos_pitch(),0.5f)) - _ahrs.sin_yaw() * _ahrs.sin_roll() / MAX(_ahrs.cos_roll(),0.5f));
track_leash_slack = MIN(_track_leash_length*(leash_z-track_error_z)/leash_z, _track_leash_length*(leash_xy-track_error_xy)/leash_xy);
RC_Channel_aux::move_servo(RC_Channel_aux::k_sprayer_pump, MIN(MAX(ground_speed * _pump_pct_1ms, 100 *_pump_min_pct),10000),0,10000);
2015-11-27 13:27:32 -04:00
|
|
|
template<typename A, typename B>
|
|
|
|
static inline auto MIN(const A &one, const B &two) -> decltype(one < two ? one : two) {
|
|
|
|
return one < two ? one : two;
|
|
|
|
}
|
|
|
|
|
|
|
|
template<typename A, typename B>
|
|
|
|
static inline auto MAX(const A &one, const B &two) -> decltype(one > two ? one : two) {
|
|
|
|
return one > two ? one : two;
|
|
|
|
}
|
2012-12-18 22:33:52 -04:00
|
|
|
|
2015-10-27 13:07:07 -03:00
|
|
|
inline uint32_t hz_to_nsec(uint32_t freq)
|
|
|
|
{
|
|
|
|
return NSEC_PER_SEC / freq;
|
|
|
|
}
|
|
|
|
|
2015-12-07 12:18:44 -04:00
|
|
|
inline uint32_t nsec_to_hz(uint32_t nsec)
|
2015-10-27 13:07:07 -03:00
|
|
|
{
|
2015-12-07 12:18:44 -04:00
|
|
|
return NSEC_PER_SEC / nsec;
|
2015-10-27 13:07:07 -03:00
|
|
|
}
|
|
|
|
|
2015-10-27 13:07:51 -03:00
|
|
|
inline uint32_t usec_to_nsec(uint32_t usec)
|
|
|
|
{
|
|
|
|
return usec * NSEC_PER_USEC;
|
|
|
|
}
|
|
|
|
|
|
|
|
inline uint32_t nsec_to_usec(uint32_t nsec)
|
|
|
|
{
|
|
|
|
return nsec / NSEC_PER_USEC;
|
|
|
|
}
|
|
|
|
|
2015-12-07 12:19:50 -04:00
|
|
|
inline uint32_t hz_to_usec(uint32_t freq)
|
|
|
|
{
|
|
|
|
return USEC_PER_SEC / freq;
|
|
|
|
}
|
|
|
|
|
|
|
|
inline uint32_t usec_to_hz(uint32_t usec)
|
|
|
|
{
|
|
|
|
return USEC_PER_SEC / usec;
|
|
|
|
}
|
|
|
|
|
2016-04-02 08:44:47 -03:00
|
|
|
/*
|
|
|
|
linear interpolation based on a variable in a range
|
|
|
|
*/
|
|
|
|
float linear_interpolate(float low_output, float high_output,
|
|
|
|
float var_value,
|
|
|
|
float var_low, float var_high);
|
|
|
|
|