mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Add an accessor for the DCM drift correction integrator to monitor performance
Also made the get_health accessor an inline function.
This commit is contained in:
parent
947950398c
commit
e3ab1b0353
@ -393,12 +393,4 @@ AP_DCM::euler_yaw(void)
|
||||
yaw_sensor += 36000;
|
||||
}
|
||||
|
||||
/**************************************************/
|
||||
|
||||
float
|
||||
AP_DCM::get_health(void)
|
||||
{
|
||||
return _health;
|
||||
}
|
||||
|
||||
|
||||
|
@ -43,7 +43,9 @@ public:
|
||||
Vector3f get_accel(void) { return _accel_vector; }
|
||||
Matrix3f get_dcm_matrix(void) {return _dcm_matrix; }
|
||||
Matrix3f get_dcm_transposed(void) {Matrix3f temp = _dcm_matrix; return temp.transpose();}
|
||||
|
||||
Vector3f get_integrator(void) {return _omega_I; } // We return the current drift correction integrator values
|
||||
|
||||
float get_health(void) {return _health;}
|
||||
void set_centripetal(bool b) {_centripetal = b;}
|
||||
bool get_centripetal(void) {return _centripetal;}
|
||||
void set_compass(Compass *compass);
|
||||
@ -52,8 +54,6 @@ public:
|
||||
void update_DCM(void);
|
||||
void update_DCM_fast(void);
|
||||
|
||||
float get_health(void);
|
||||
|
||||
long roll_sensor; // Degrees * 100
|
||||
long pitch_sensor; // Degrees * 100
|
||||
long yaw_sensor; // Degrees * 100
|
||||
|
Loading…
Reference in New Issue
Block a user