mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Math: compiler warnings: float to double promotion
cast as float because we're in magical template land where T minus T means promote to double
This commit is contained in:
parent
1c3ad00aa7
commit
820f0bf02a
@ -20,6 +20,7 @@
|
|||||||
#include "polygon.h"
|
#include "polygon.h"
|
||||||
#include "edc.h"
|
#include "edc.h"
|
||||||
#include "float.h"
|
#include "float.h"
|
||||||
|
#include "AP_Param.h"
|
||||||
|
|
||||||
#ifndef M_PI_F
|
#ifndef M_PI_F
|
||||||
#define M_PI_F 3.141592653589793f
|
#define M_PI_F 3.141592653589793f
|
||||||
|
@ -19,7 +19,7 @@
|
|||||||
|
|
||||||
#include "AP_Math.h"
|
#include "AP_Math.h"
|
||||||
|
|
||||||
#define HALF_SQRT_2 0.70710678118654757
|
#define HALF_SQRT_2 0.70710678118654757f
|
||||||
|
|
||||||
// rotate a vector by a standard rotation, attempting
|
// rotate a vector by a standard rotation, attempting
|
||||||
// to use the minimum number of floating point operations
|
// to use the minimum number of floating point operations
|
||||||
@ -32,8 +32,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
case ROTATION_MAX:
|
case ROTATION_MAX:
|
||||||
return;
|
return;
|
||||||
case ROTATION_YAW_45: {
|
case ROTATION_YAW_45: {
|
||||||
tmp = HALF_SQRT_2*(x - y);
|
tmp = HALF_SQRT_2*(float)(x - y);
|
||||||
y = HALF_SQRT_2*(x + y);
|
y = HALF_SQRT_2*(float)(x + y);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -42,8 +42,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
case ROTATION_YAW_135: {
|
case ROTATION_YAW_135: {
|
||||||
tmp = -HALF_SQRT_2*(x + y);
|
tmp = -HALF_SQRT_2*(float)(x + y);
|
||||||
y = HALF_SQRT_2*(x - y);
|
y = HALF_SQRT_2*(float)(x - y);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -51,8 +51,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
x = -x; y = -y;
|
x = -x; y = -y;
|
||||||
return;
|
return;
|
||||||
case ROTATION_YAW_225: {
|
case ROTATION_YAW_225: {
|
||||||
tmp = HALF_SQRT_2*(y - x);
|
tmp = HALF_SQRT_2*(float)(y - x);
|
||||||
y = -HALF_SQRT_2*(x + y);
|
y = -HALF_SQRT_2*(float)(x + y);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -61,8 +61,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
case ROTATION_YAW_315: {
|
case ROTATION_YAW_315: {
|
||||||
tmp = HALF_SQRT_2*(x + y);
|
tmp = HALF_SQRT_2*(float)(x + y);
|
||||||
y = HALF_SQRT_2*(y - x);
|
y = HALF_SQRT_2*(float)(y - x);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -71,8 +71,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
case ROTATION_ROLL_180_YAW_45: {
|
case ROTATION_ROLL_180_YAW_45: {
|
||||||
tmp = HALF_SQRT_2*(x + y);
|
tmp = HALF_SQRT_2*(float)(x + y);
|
||||||
y = HALF_SQRT_2*(x - y);
|
y = HALF_SQRT_2*(float)(x - y);
|
||||||
x = tmp; z = -z;
|
x = tmp; z = -z;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -81,8 +81,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
case ROTATION_ROLL_180_YAW_135: {
|
case ROTATION_ROLL_180_YAW_135: {
|
||||||
tmp = HALF_SQRT_2*(y - x);
|
tmp = HALF_SQRT_2*(float)(y - x);
|
||||||
y = HALF_SQRT_2*(y + x);
|
y = HALF_SQRT_2*(float)(y + x);
|
||||||
x = tmp; z = -z;
|
x = tmp; z = -z;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -91,8 +91,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
case ROTATION_ROLL_180_YAW_225: {
|
case ROTATION_ROLL_180_YAW_225: {
|
||||||
tmp = -HALF_SQRT_2*(x + y);
|
tmp = -HALF_SQRT_2*(float)(x + y);
|
||||||
y = HALF_SQRT_2*(y - x);
|
y = HALF_SQRT_2*(float)(y - x);
|
||||||
x = tmp; z = -z;
|
x = tmp; z = -z;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -101,8 +101,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
case ROTATION_ROLL_180_YAW_315: {
|
case ROTATION_ROLL_180_YAW_315: {
|
||||||
tmp = HALF_SQRT_2*(x - y);
|
tmp = HALF_SQRT_2*(float)(x - y);
|
||||||
y = -HALF_SQRT_2*(x + y);
|
y = -HALF_SQRT_2*(float)(x + y);
|
||||||
x = tmp; z = -z;
|
x = tmp; z = -z;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -112,8 +112,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
}
|
}
|
||||||
case ROTATION_ROLL_90_YAW_45: {
|
case ROTATION_ROLL_90_YAW_45: {
|
||||||
tmp = z; z = y; y = -tmp;
|
tmp = z; z = y; y = -tmp;
|
||||||
tmp = HALF_SQRT_2*(x - y);
|
tmp = HALF_SQRT_2*(float)(x - y);
|
||||||
y = HALF_SQRT_2*(x + y);
|
y = HALF_SQRT_2*(float)(x + y);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -124,8 +124,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
}
|
}
|
||||||
case ROTATION_ROLL_90_YAW_135: {
|
case ROTATION_ROLL_90_YAW_135: {
|
||||||
tmp = z; z = y; y = -tmp;
|
tmp = z; z = y; y = -tmp;
|
||||||
tmp = -HALF_SQRT_2*(x + y);
|
tmp = -HALF_SQRT_2*(float)(x + y);
|
||||||
y = HALF_SQRT_2*(x - y);
|
y = HALF_SQRT_2*(float)(x - y);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -135,8 +135,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
}
|
}
|
||||||
case ROTATION_ROLL_270_YAW_45: {
|
case ROTATION_ROLL_270_YAW_45: {
|
||||||
tmp = z; z = -y; y = tmp;
|
tmp = z; z = -y; y = tmp;
|
||||||
tmp = HALF_SQRT_2*(x - y);
|
tmp = HALF_SQRT_2*(float)(x - y);
|
||||||
y = HALF_SQRT_2*(x + y);
|
y = HALF_SQRT_2*(float)(x + y);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -147,8 +147,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
}
|
}
|
||||||
case ROTATION_ROLL_270_YAW_135: {
|
case ROTATION_ROLL_270_YAW_135: {
|
||||||
tmp = z; z = -y; y = tmp;
|
tmp = z; z = -y; y = tmp;
|
||||||
tmp = -HALF_SQRT_2*(x + y);
|
tmp = -HALF_SQRT_2*(float)(x + y);
|
||||||
y = HALF_SQRT_2*(x - y);
|
y = HALF_SQRT_2*(float)(x - y);
|
||||||
x = tmp;
|
x = tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -339,7 +339,7 @@ bool Vector3<T>::operator !=(const Vector3<T> &v) const
|
|||||||
template <typename T>
|
template <typename T>
|
||||||
float Vector3<T>::angle(const Vector3<T> &v2) const
|
float Vector3<T>::angle(const Vector3<T> &v2) const
|
||||||
{
|
{
|
||||||
return acosf(((*this)*v2) / (this->length()*v2.length()));
|
return acosf((*this)*v2) / (float)((this->length()*v2.length()));
|
||||||
}
|
}
|
||||||
|
|
||||||
// multiplication of transpose by a vector
|
// multiplication of transpose by a vector
|
||||||
|
Loading…
Reference in New Issue
Block a user