APM:Libraries
AP_AHRS_View.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AHRS View class - for creating a 2nd view of the vehicle attitude
18  *
19  */
20 
21 #include "AP_AHRS_View.h"
22 #include <stdio.h>
23 
24 AP_AHRS_View::AP_AHRS_View(AP_AHRS &_ahrs, enum Rotation _rotation) :
25  rotation(_rotation),
26  ahrs(_ahrs)
27 {
28  switch (rotation) {
29  case ROTATION_NONE:
31  break;
32  case ROTATION_PITCH_90:
33  rot_view.from_euler(0, radians(90), 0);
34  break;
35  case ROTATION_PITCH_270:
36  rot_view.from_euler(0, radians(270), 0);
37  break;
38  default:
39  AP_HAL::panic("Unsupported AHRS view %u\n", (unsigned)rotation);
40  }
41 
42  // setup initial state
43  update();
44 }
45 
46 // update state
47 void AP_AHRS_View::update(bool skip_ins_update)
48 {
50  gyro = ahrs.get_gyro();
51 
52  if (rotation != ROTATION_NONE) {
54  r.transpose();
55  r = rot_view * r;
56  r.transpose();
58  }
59 
61 
62  roll_sensor = degrees(roll) * 100;
63  pitch_sensor = degrees(pitch) * 100;
64  yaw_sensor = degrees(yaw) * 100;
65  if (yaw_sensor < 0) {
66  yaw_sensor += 36000;
67  }
68 
70  trig.cos_roll, trig.cos_pitch, trig.cos_yaw,
71  trig.sin_roll, trig.sin_pitch, trig.sin_yaw);
72 }
73 
74 // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
76  Vector3f gyro_latest = ahrs.get_gyro_latest();
77  gyro_latest.rotate(rotation);
78  return gyro_latest;
79 }
80 
81 // rotate a 2D vector from earth frame to body frame
83 {
84  return Vector2f(ef.x * trig.cos_yaw + ef.y * trig.sin_yaw,
85  -ef.x * trig.sin_yaw + ef.y * trig.cos_yaw);
86 }
87 
88 // rotate a 2D vector from earth frame to body frame
90 {
91  return Vector2f(bf.x * trig.cos_yaw - bf.y * trig.sin_yaw,
92  bf.x * trig.sin_yaw + bf.y * trig.cos_yaw);
93 }
Vector2f rotate_earth_to_body2D(const Vector2f &ef_vector) const
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
Vector2< float > Vector2f
Definition: vector2.h:239
int32_t pitch_sensor
Definition: AP_AHRS_View.h:172
Vector3f gyro
Definition: AP_AHRS_View.h:181
AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation)
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
virtual const Vector3f & get_gyro(void) const =0
struct AP_AHRS_View::@4 trig
Matrix3f rot_body_to_ned
Definition: AP_AHRS_View.h:180
int32_t yaw_sensor
Definition: AP_AHRS_View.h:173
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
Vector3f get_gyro_latest(void) const
enum Rotation rotation
Definition: AP_AHRS_View.h:176
Vector2f rotate_body_to_earth2D(const Vector2f &bf) const
virtual const Matrix3f & get_rotation_body_to_ned(void) const =0
Rotation
Definition: rotations.h:27
AP_AHRS & ahrs
Definition: AP_AHRS_View.h:177
T y
Definition: vector2.h:37
void update(bool skip_ins_update=false)
Vector3f get_gyro_latest(void) const
Definition: AP_AHRS.cpp:163
void rotate(enum Rotation rotation)
Definition: vector3.cpp:28
Matrix3f rot_view
Definition: AP_AHRS_View.h:179
T x
Definition: vector2.h:37
void transpose(void)
Definition: matrix3.h:185
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void calc_trig(const Matrix3f &rot, float &cr, float &cp, float &cy, float &sr, float &sp, float &sy) const
Definition: AP_AHRS.cpp:290
#define degrees(x)
Definition: moduletest.c:23
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
int32_t roll_sensor
Definition: AP_AHRS_View.h:171
void identity(void)
Definition: matrix3.h:219