|
|
|
@ -15,7 +15,9 @@
@@ -15,7 +15,9 @@
|
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
|
*/ |
|
|
|
|
#include "AP_AHRS.h" |
|
|
|
|
#include "AP_AHRS_View.h" |
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
// table of user settable parameters
|
|
|
|
@ -229,61 +231,68 @@ Vector2f AP_AHRS::groundspeed_vector(void)
@@ -229,61 +231,68 @@ Vector2f AP_AHRS::groundspeed_vector(void)
|
|
|
|
|
return Vector2f(0.0f, 0.0f); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
|
|
|
|
|
// should be called after _dcm_matrix is updated
|
|
|
|
|
void AP_AHRS::update_trig(void) |
|
|
|
|
/*
|
|
|
|
|
calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix |
|
|
|
|
*/ |
|
|
|
|
void AP_AHRS::calc_trig(const Matrix3f &rot, |
|
|
|
|
float &cr, float &cp, float &cy, |
|
|
|
|
float &sr, float &sp, float &sy) const |
|
|
|
|
{ |
|
|
|
|
if (_last_trim != _trim.get()) { |
|
|
|
|
_last_trim = _trim.get(); |
|
|
|
|
_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, 0.0f); |
|
|
|
|
_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
Vector2f yaw_vector; |
|
|
|
|
const Matrix3f &temp = get_rotation_body_to_ned(); |
|
|
|
|
|
|
|
|
|
// sin_yaw, cos_yaw
|
|
|
|
|
yaw_vector.x = temp.a.x; |
|
|
|
|
yaw_vector.y = temp.b.x; |
|
|
|
|
yaw_vector.normalize(); |
|
|
|
|
_sin_yaw = constrain_float(yaw_vector.y, -1.0, 1.0); |
|
|
|
|
_cos_yaw = constrain_float(yaw_vector.x, -1.0, 1.0); |
|
|
|
|
yaw_vector.x = rot.a.x; |
|
|
|
|
yaw_vector.y = rot.b.x; |
|
|
|
|
if (fabsf(yaw_vector.x) > 0 || |
|
|
|
|
fabsf(yaw_vector.y) > 0) { |
|
|
|
|
yaw_vector.normalize(); |
|
|
|
|
} |
|
|
|
|
sy = constrain_float(yaw_vector.y, -1.0, 1.0); |
|
|
|
|
cy = constrain_float(yaw_vector.x, -1.0, 1.0); |
|
|
|
|
|
|
|
|
|
// cos_roll, cos_pitch
|
|
|
|
|
float cx2 = temp.c.x * temp.c.x; |
|
|
|
|
// sanity checks
|
|
|
|
|
if (yaw_vector.is_inf() || yaw_vector.is_nan()) { |
|
|
|
|
sy = 0.0f; |
|
|
|
|
cy = 1.0f; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
float cx2 = rot.c.x * rot.c.x; |
|
|
|
|
if (cx2 >= 1.0f) { |
|
|
|
|
_cos_pitch = 0; |
|
|
|
|
_cos_roll = 1.0f; |
|
|
|
|
cp = 0; |
|
|
|
|
cr = 1.0f; |
|
|
|
|
} else { |
|
|
|
|
_cos_pitch = safe_sqrt(1 - cx2); |
|
|
|
|
_cos_roll = temp.c.z / _cos_pitch; |
|
|
|
|
cp = safe_sqrt(1 - cx2); |
|
|
|
|
cr = rot.c.z / cp; |
|
|
|
|
} |
|
|
|
|
_cos_pitch = constrain_float(_cos_pitch, 0, 1.0); |
|
|
|
|
_cos_roll = constrain_float(_cos_roll, -1.0, 1.0); // this relies on constrain_float() of infinity doing the right thing
|
|
|
|
|
cp = constrain_float(cp, 0, 1.0); |
|
|
|
|
cr = constrain_float(cr, -1.0, 1.0); // this relies on constrain_float() of infinity doing the right thing
|
|
|
|
|
|
|
|
|
|
// sin_roll, sin_pitch
|
|
|
|
|
_sin_pitch = -temp.c.x; |
|
|
|
|
if (is_zero(_cos_pitch)) { |
|
|
|
|
_sin_roll = sinf(roll); |
|
|
|
|
} else { |
|
|
|
|
_sin_roll = temp.c.y / _cos_pitch; |
|
|
|
|
} |
|
|
|
|
sp = -rot.c.x; |
|
|
|
|
|
|
|
|
|
// sanity checks
|
|
|
|
|
if (yaw_vector.is_inf() || yaw_vector.is_nan()) { |
|
|
|
|
yaw_vector.x = 0.0f; |
|
|
|
|
yaw_vector.y = 0.0f; |
|
|
|
|
_sin_yaw = 0.0f; |
|
|
|
|
_cos_yaw = 1.0f; |
|
|
|
|
if (!is_zero(cp)) { |
|
|
|
|
sr = rot.c.y / cp; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (isinf(_cos_roll) || isnan(_cos_roll)) { |
|
|
|
|
_cos_roll = cosf(roll); |
|
|
|
|
if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) { |
|
|
|
|
float r, p, y; |
|
|
|
|
rot.to_euler(&r, &p, &y); |
|
|
|
|
cr = cosf(r); |
|
|
|
|
sr = sinf(r); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (isinf(_sin_roll) || isnan(_sin_roll)) { |
|
|
|
|
_sin_roll = sinf(roll); |
|
|
|
|
// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
|
|
|
|
|
// should be called after _dcm_matrix is updated
|
|
|
|
|
void AP_AHRS::update_trig(void) |
|
|
|
|
{ |
|
|
|
|
if (_last_trim != _trim.get()) { |
|
|
|
|
_last_trim = _trim.get(); |
|
|
|
|
_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, 0.0f); |
|
|
|
|
_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
calc_trig(get_rotation_body_to_ned(), |
|
|
|
|
_cos_roll, _cos_pitch, _cos_yaw, |
|
|
|
|
_sin_roll, _sin_pitch, _sin_yaw); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
@ -297,3 +306,16 @@ void AP_AHRS::update_cd_values(void)
@@ -297,3 +306,16 @@ void AP_AHRS::update_cd_values(void)
|
|
|
|
|
if (yaw_sensor < 0) |
|
|
|
|
yaw_sensor += 36000; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
create a rotated view of AP_AHRS |
|
|
|
|
*/ |
|
|
|
|
AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation) |
|
|
|
|
{ |
|
|
|
|
if (_view != nullptr) { |
|
|
|
|
// can only have one
|
|
|
|
|
return nullptr; |
|
|
|
|
} |
|
|
|
|
_view = new AP_AHRS_View(*this, rotation); |
|
|
|
|
return _view; |
|
|
|
|
} |
|
|
|
|