Browse Source

AP_AHRS: add trimed view

mission-4.1.18
IamPete1 6 years ago committed by Andrew Tridgell
parent
commit
e1cdf9fe0a
  1. 6
      libraries/AP_AHRS/AP_AHRS.cpp
  2. 7
      libraries/AP_AHRS/AP_AHRS.h
  3. 14
      libraries/AP_AHRS/AP_AHRS_View.cpp
  4. 6
      libraries/AP_AHRS/AP_AHRS_View.h

6
libraries/AP_AHRS/AP_AHRS.cpp

@ -359,15 +359,15 @@ void AP_AHRS::update_cd_values(void)
} }
/* /*
create a rotated view of AP_AHRS create a rotated view of AP_AHRS with pitch trim
*/ */
AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation) AP_AHRS_View *AP_AHRS::create_view_trim(enum Rotation rotation, float pitch_trim)
{ {
if (_view != nullptr) { if (_view != nullptr) {
// can only have one // can only have one
return nullptr; return nullptr;
} }
_view = new AP_AHRS_View(*this, rotation); _view = new AP_AHRS_View(*this, rotation, pitch_trim);
return _view; return _view;
} }

7
libraries/AP_AHRS/AP_AHRS.h

@ -546,7 +546,12 @@ public:
} }
// create a view // create a view
AP_AHRS_View *create_view(enum Rotation rotation); AP_AHRS_View *create_view(enum Rotation rotation) {
return create_view_trim(rotation, 0.0f);
}
// create a view with pitch trim
AP_AHRS_View *create_view_trim(enum Rotation rotation, float pitch_trim);
// return calculated AOA // return calculated AOA
float getAOA(void); float getAOA(void);

14
libraries/AP_AHRS/AP_AHRS_View.cpp

@ -21,24 +21,28 @@
#include "AP_AHRS_View.h" #include "AP_AHRS_View.h"
#include <stdio.h> #include <stdio.h>
AP_AHRS_View::AP_AHRS_View(AP_AHRS &_ahrs, enum Rotation _rotation) : AP_AHRS_View::AP_AHRS_View(AP_AHRS &_ahrs, enum Rotation _rotation, float pitch_trim) :
rotation(_rotation), rotation(_rotation),
ahrs(_ahrs) ahrs(_ahrs)
{ {
switch (rotation) { switch (rotation) {
case ROTATION_NONE: case ROTATION_NONE:
rot_view.identity();
break; break;
case ROTATION_PITCH_90: case ROTATION_PITCH_90:
rot_view.from_euler(0, radians(90), 0); y_angle = 90;
break; break;
case ROTATION_PITCH_270: case ROTATION_PITCH_270:
rot_view.from_euler(0, radians(270), 0); y_angle = 270;
break; break;
default: default:
AP_HAL::panic("Unsupported AHRS view %u\n", (unsigned)rotation); AP_HAL::panic("Unsupported AHRS view %u\n", (unsigned)rotation);
} }
// Add pitch trim
y_angle = wrap_360(y_angle + pitch_trim);
rot_view.from_euler(radians(x_angle), radians(y_angle), radians(z_angle));
// setup initial state // setup initial state
update(); update();
} }
@ -49,7 +53,7 @@ void AP_AHRS_View::update(bool skip_ins_update)
rot_body_to_ned = ahrs.get_rotation_body_to_ned(); rot_body_to_ned = ahrs.get_rotation_body_to_ned();
gyro = ahrs.get_gyro(); gyro = ahrs.get_gyro();
if (rotation != ROTATION_NONE) { if (!is_zero(x_angle) || !is_zero(y_angle) || !is_zero(z_angle)) {
Matrix3f &r = rot_body_to_ned; Matrix3f &r = rot_body_to_ned;
r.transpose(); r.transpose();
r = rot_view * r; r = rot_view * r;

6
libraries/AP_AHRS/AP_AHRS_View.h

@ -26,7 +26,7 @@ class AP_AHRS_View
{ {
public: public:
// Constructor // Constructor
AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation); AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation, float pitch_trim);
// update state // update state
void update(bool skip_ins_update=false); void update(bool skip_ins_update=false);
@ -188,4 +188,8 @@ private:
float sin_pitch; float sin_pitch;
float sin_yaw; float sin_yaw;
} trig; } trig;
float x_angle;
float y_angle;
float z_angle;
}; };

Loading…
Cancel
Save