Browse Source

AP_AHRS: added optional skip_ins_update to AHRS::update()

avoid the ins update if already done in copter fast_loop()
master
Andrew Tridgell 8 years ago committed by Randy Mackay
parent
commit
a11dca5229
  1. 2
      libraries/AP_AHRS/AP_AHRS.h
  2. 8
      libraries/AP_AHRS/AP_AHRS_DCM.cpp
  3. 2
      libraries/AP_AHRS/AP_AHRS_DCM.h
  4. 10
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  5. 4
      libraries/AP_AHRS/AP_AHRS_NavEKF.h
  6. 2
      libraries/AP_AHRS/AP_AHRS_View.cpp
  7. 2
      libraries/AP_AHRS/AP_AHRS_View.h

2
libraries/AP_AHRS/AP_AHRS.h

@ -210,7 +210,7 @@ public: @@ -210,7 +210,7 @@ public:
}
// Methods
virtual void update(void) = 0;
virtual void update(bool skip_ins_update=false) = 0;
// report any reason for why the backend is refusing to initialise
virtual const char *prearm_failure_reason(void) const {

8
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -47,7 +47,7 @@ AP_AHRS_DCM::reset_gyro_drift(void) @@ -47,7 +47,7 @@ AP_AHRS_DCM::reset_gyro_drift(void)
// run a full DCM update round
void
AP_AHRS_DCM::update(void)
AP_AHRS_DCM::update(bool skip_ins_update)
{
float delta_t;
@ -55,8 +55,10 @@ AP_AHRS_DCM::update(void) @@ -55,8 +55,10 @@ AP_AHRS_DCM::update(void)
_last_startup_ms = AP_HAL::millis();
}
// tell the IMU to grab some data
_ins.update();
if (!skip_ins_update) {
// tell the IMU to grab some data
_ins.update();
}
// ask the IMU how much time this sensor reading represents
delta_t = _ins.get_delta_time();

2
libraries/AP_AHRS/AP_AHRS_DCM.h

@ -78,7 +78,7 @@ public: @@ -78,7 +78,7 @@ public:
void reset_gyro_drift() override;
// Methods
void update() override;
void update(bool skip_ins_update=false) override;
void reset(bool recover_eulers = false) override;
// reset the current attitude, used on new IMU calibration

10
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -79,13 +79,13 @@ void AP_AHRS_NavEKF::reset_gyro_drift(void) @@ -79,13 +79,13 @@ void AP_AHRS_NavEKF::reset_gyro_drift(void)
EKF3.resetGyroBias();
}
void AP_AHRS_NavEKF::update(void)
void AP_AHRS_NavEKF::update(bool skip_ins_update)
{
// EKF1 is no longer supported - handle case where it is selected
if (_ekf_type == 1) {
_ekf_type.set(2);
}
update_DCM();
update_DCM(skip_ins_update);
update_EKF2();
update_EKF3();
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
@ -103,11 +103,11 @@ void AP_AHRS_NavEKF::update(void) @@ -103,11 +103,11 @@ void AP_AHRS_NavEKF::update(void)
if (_view != nullptr) {
// update optional alternative attitude view
_view->update();
_view->update(skip_ins_update);
}
}
void AP_AHRS_NavEKF::update_DCM(void)
void AP_AHRS_NavEKF::update_DCM(bool skip_ins_update)
{
// we need to restore the old DCM attitude values as these are
// used internally in DCM to calculate error values for gyro drift
@ -117,7 +117,7 @@ void AP_AHRS_NavEKF::update_DCM(void) @@ -117,7 +117,7 @@ void AP_AHRS_NavEKF::update_DCM(void)
yaw = _dcm_attitude.z;
update_cd_values();
AP_AHRS_DCM::update();
AP_AHRS_DCM::update(skip_ins_update);
// keep DCM attitude available for get_secondary_attitude()
_dcm_attitude(roll, pitch, yaw);

4
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -59,7 +59,7 @@ public: @@ -59,7 +59,7 @@ public:
// should be called if gyro offsets are recalculated
void reset_gyro_drift() override;
void update() override;
void update(bool skip_ins_update=false) override;
void reset(bool recover_eulers = false) override;
// reset the current attitude, used on new IMU calibration
@ -268,7 +268,7 @@ private: @@ -268,7 +268,7 @@ private:
Flags _ekf_flags;
uint8_t ekf_type(void) const;
void update_DCM(void);
void update_DCM(bool skip_ins_update);
void update_EKF2(void);
void update_EKF3(void);

2
libraries/AP_AHRS/AP_AHRS_View.cpp

@ -44,7 +44,7 @@ AP_AHRS_View::AP_AHRS_View(AP_AHRS &_ahrs, enum Rotation _rotation) : @@ -44,7 +44,7 @@ AP_AHRS_View::AP_AHRS_View(AP_AHRS &_ahrs, enum Rotation _rotation) :
}
// update state
void AP_AHRS_View::update(void)
void AP_AHRS_View::update(bool skip_ins_update)
{
rot_body_to_ned = ahrs.get_rotation_body_to_ned();
gyro = ahrs.get_gyro();

2
libraries/AP_AHRS/AP_AHRS_View.h

@ -29,7 +29,7 @@ public: @@ -29,7 +29,7 @@ public:
AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation);
// update state
void update(void);
void update(bool skip_ins_update=false);
// empty virtual destructor
virtual ~AP_AHRS_View() {}

Loading…
Cancel
Save