mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_AHRS: save memory and reduce pointer references
use a refence for ins, and don't save gyro and accel between updates
This commit is contained in:
parent
cb52b6f367
commit
d31e557983
@ -37,7 +37,7 @@ class AP_AHRS
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// Constructor
|
// Constructor
|
||||||
AP_AHRS(AP_InertialSensor *ins, GPS *&gps) :
|
AP_AHRS(AP_InertialSensor &ins, GPS *&gps) :
|
||||||
_ins(ins),
|
_ins(ins),
|
||||||
_gps(gps)
|
_gps(gps)
|
||||||
{
|
{
|
||||||
@ -49,7 +49,7 @@ public:
|
|||||||
// prone than the APM1, so we should have a lower ki,
|
// prone than the APM1, so we should have a lower ki,
|
||||||
// which will make us less prone to increasing omegaI
|
// which will make us less prone to increasing omegaI
|
||||||
// incorrectly due to sensor noise
|
// incorrectly due to sensor noise
|
||||||
_gyro_drift_limit = ins->get_gyro_drift_rate();
|
_gyro_drift_limit = ins.get_gyro_drift_rate();
|
||||||
|
|
||||||
// enable centrifugal correction by default
|
// enable centrifugal correction by default
|
||||||
_flags.correct_centrifugal = true;
|
_flags.correct_centrifugal = true;
|
||||||
@ -78,7 +78,7 @@ public:
|
|||||||
// allow for runtime change of orientation
|
// allow for runtime change of orientation
|
||||||
// this makes initial config easier
|
// this makes initial config easier
|
||||||
void set_orientation() {
|
void set_orientation() {
|
||||||
_ins->set_board_orientation((enum Rotation)_board_orientation.get());
|
_ins.set_board_orientation((enum Rotation)_board_orientation.get());
|
||||||
if (_compass != NULL) {
|
if (_compass != NULL) {
|
||||||
_compass->set_board_orientation((enum Rotation)_board_orientation.get());
|
_compass->set_board_orientation((enum Rotation)_board_orientation.get());
|
||||||
}
|
}
|
||||||
@ -88,7 +88,7 @@ public:
|
|||||||
_airspeed = airspeed;
|
_airspeed = airspeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_InertialSensor* get_ins() const {
|
const AP_InertialSensor &get_ins() const {
|
||||||
return _ins;
|
return _ins;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -263,7 +263,7 @@ protected:
|
|||||||
|
|
||||||
// note: we use ref-to-pointer here so that our caller can change the GPS without our noticing
|
// note: we use ref-to-pointer here so that our caller can change the GPS without our noticing
|
||||||
// IMU under us without our noticing.
|
// IMU under us without our noticing.
|
||||||
AP_InertialSensor *_ins;
|
AP_InertialSensor &_ins;
|
||||||
GPS *&_gps;
|
GPS *&_gps;
|
||||||
|
|
||||||
// a vector to capture the difference between the controller and body frames
|
// a vector to capture the difference between the controller and body frames
|
||||||
|
@ -48,10 +48,10 @@ AP_AHRS_DCM::update(void)
|
|||||||
float delta_t;
|
float delta_t;
|
||||||
|
|
||||||
// tell the IMU to grab some data
|
// tell the IMU to grab some data
|
||||||
_ins->update();
|
_ins.update();
|
||||||
|
|
||||||
// ask the IMU how much time this sensor reading represents
|
// ask the IMU how much time this sensor reading represents
|
||||||
delta_t = _ins->get_delta_time();
|
delta_t = _ins.get_delta_time();
|
||||||
|
|
||||||
// if the update call took more than 0.2 seconds then discard it,
|
// if the update call took more than 0.2 seconds then discard it,
|
||||||
// otherwise we may move too far. This happens when arming motors
|
// otherwise we may move too far. This happens when arming motors
|
||||||
@ -62,10 +62,6 @@ AP_AHRS_DCM::update(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get current values for gyros
|
|
||||||
_gyro_vector = _ins->get_gyro();
|
|
||||||
_accel_vector = _ins->get_accel();
|
|
||||||
|
|
||||||
// Integrate the DCM matrix using gyro inputs
|
// Integrate the DCM matrix using gyro inputs
|
||||||
matrix_update(delta_t);
|
matrix_update(delta_t);
|
||||||
|
|
||||||
@ -91,7 +87,7 @@ AP_AHRS_DCM::matrix_update(float _G_Dt)
|
|||||||
// and including the P terms would give positive feedback into
|
// and including the P terms would give positive feedback into
|
||||||
// the _P_gain() calculation, which can lead to a very large P
|
// the _P_gain() calculation, which can lead to a very large P
|
||||||
// value
|
// value
|
||||||
_omega = _gyro_vector + _omega_I;
|
_omega = _ins.get_gyro() + _omega_I;
|
||||||
|
|
||||||
_dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * _G_Dt);
|
_dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * _G_Dt);
|
||||||
}
|
}
|
||||||
@ -461,7 +457,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
|||||||
temp_dcm.rotateXY(_trim);
|
temp_dcm.rotateXY(_trim);
|
||||||
|
|
||||||
// rotate accelerometer values into the earth frame
|
// rotate accelerometer values into the earth frame
|
||||||
_accel_ef = temp_dcm * _accel_vector;
|
_accel_ef = temp_dcm * _ins.get_accel();
|
||||||
|
|
||||||
// integrate the accel vector in the earth frame between GPS readings
|
// integrate the accel vector in the earth frame between GPS readings
|
||||||
_ra_sum += _accel_ef * deltat;
|
_ra_sum += _accel_ef * deltat;
|
||||||
@ -625,7 +621,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
|||||||
|
|
||||||
if (_flags.fly_forward && _gps && _gps->status() >= GPS::GPS_OK_FIX_2D &&
|
if (_flags.fly_forward && _gps && _gps->status() >= GPS::GPS_OK_FIX_2D &&
|
||||||
_gps->ground_speed_cm < GPS_SPEED_MIN &&
|
_gps->ground_speed_cm < GPS_SPEED_MIN &&
|
||||||
_accel_vector.x >= 7 &&
|
_ins.get_accel().x >= 7 &&
|
||||||
pitch_sensor > -3000 && pitch_sensor < 3000) {
|
pitch_sensor > -3000 && pitch_sensor < 3000) {
|
||||||
// assume we are in a launch acceleration, and reduce the
|
// assume we are in a launch acceleration, and reduce the
|
||||||
// rp gain by 50% to reduce the impact of GPS lag on
|
// rp gain by 50% to reduce the impact of GPS lag on
|
||||||
|
@ -25,7 +25,7 @@ class AP_AHRS_DCM : public AP_AHRS
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// Constructors
|
// Constructors
|
||||||
AP_AHRS_DCM(AP_InertialSensor *ins, GPS *&gps) :
|
AP_AHRS_DCM(AP_InertialSensor &ins, GPS *&gps) :
|
||||||
AP_AHRS(ins, gps),
|
AP_AHRS(ins, gps),
|
||||||
_last_declination(0),
|
_last_declination(0),
|
||||||
_mag_earth(1,0)
|
_mag_earth(1,0)
|
||||||
@ -92,9 +92,6 @@ private:
|
|||||||
// primary representation of attitude
|
// primary representation of attitude
|
||||||
Matrix3f _dcm_matrix;
|
Matrix3f _dcm_matrix;
|
||||||
|
|
||||||
Vector3f _gyro_vector; // Store the gyros turn rate in a vector
|
|
||||||
Vector3f _accel_vector; // current accel vector
|
|
||||||
|
|
||||||
Vector3f _omega_P; // accel Omega proportional correction
|
Vector3f _omega_P; // accel Omega proportional correction
|
||||||
Vector3f _omega_yaw_P; // proportional yaw correction
|
Vector3f _omega_yaw_P; // proportional yaw correction
|
||||||
Vector3f _omega_I; // Omega Integrator correction
|
Vector3f _omega_I; // Omega Integrator correction
|
||||||
|
@ -5,7 +5,7 @@ class AP_AHRS_HIL : public AP_AHRS
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// Constructors
|
// Constructors
|
||||||
AP_AHRS_HIL(AP_InertialSensor *ins, GPS *&gps) :
|
AP_AHRS_HIL(AP_InertialSensor &ins, GPS *&gps) :
|
||||||
AP_AHRS(ins, gps),
|
AP_AHRS(ins, gps),
|
||||||
_drift()
|
_drift()
|
||||||
{}
|
{}
|
||||||
@ -21,7 +21,7 @@ public:
|
|||||||
|
|
||||||
// Methods
|
// Methods
|
||||||
void update(void) {
|
void update(void) {
|
||||||
_ins->update();
|
_ins.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
void setHil(float roll, float pitch, float yaw,
|
void setHil(float roll, float pitch, float yaw,
|
||||||
|
@ -48,7 +48,7 @@ GPS *g_gps;
|
|||||||
AP_GPS_Auto g_gps_driver(&g_gps);
|
AP_GPS_Auto g_gps_driver(&g_gps);
|
||||||
|
|
||||||
// choose which AHRS system to use
|
// choose which AHRS system to use
|
||||||
AP_AHRS_DCM ahrs(&ins, g_gps);
|
AP_AHRS_DCM ahrs(ins, g_gps);
|
||||||
|
|
||||||
AP_Baro_HIL barometer;
|
AP_Baro_HIL barometer;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user