Sub: view update does not take skip_ins_update

This commit is contained in:
Peter Barker 2021-08-26 14:55:18 +10:00 committed by Peter Barker
parent 9dbd9d1e06
commit 29d2eed9e4
5 changed files with 5 additions and 5 deletions

View File

@ -293,7 +293,7 @@ void Sub::read_AHRS()
//----------------------------------------------- //-----------------------------------------------
// <true> tells AHRS to skip INS update as we have already done it in fast_loop() // <true> tells AHRS to skip INS update as we have already done it in fast_loop()
ahrs.update(true); ahrs.update(true);
ahrs_view.update(true); ahrs_view.update();
} }
// read baro and rangefinder altitude at 10hz // read baro and rangefinder altitude at 10hz

View File

@ -410,7 +410,7 @@ void AP_AHRS::update_DCM()
yaw = _dcm_attitude.z; yaw = _dcm_attitude.z;
update_cd_values(); update_cd_values();
AP_AHRS_DCM::update(); AP_AHRS_DCM::_update();
// keep DCM attitude available for get_secondary_attitude() // keep DCM attitude available for get_secondary_attitude()
_dcm_attitude = {roll, pitch, yaw}; _dcm_attitude = {roll, pitch, yaw};

View File

@ -78,7 +78,7 @@ public:
} }
// Methods // Methods
virtual void update() = 0; virtual void _update() = 0;
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message // returns false if we fail arming checks, in which case the buffer will be populated with a failure message
// requires_position should be true if horizontal position configuration should be checked // requires_position should be true if horizontal position configuration should be checked

View File

@ -65,7 +65,7 @@ void AP_AHRS::load_watchdog_home()
// run a full DCM update round // run a full DCM update round
void void
AP_AHRS_DCM::update() AP_AHRS_DCM::_update()
{ {
AP_InertialSensor &_ins = AP::ins(); AP_InertialSensor &_ins = AP::ins();

View File

@ -58,7 +58,7 @@ public:
void reset_gyro_drift() override; void reset_gyro_drift() override;
// Methods // Methods
void update() override; void _update() override;
void reset(bool recover_eulers = false) override; void reset(bool recover_eulers = false) override;
// return true if yaw has been initialised // return true if yaw has been initialised