mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: move logging of SIMSTATE, AHRS2 and POS into AP_AHRS library
This commit is contained in:
parent
2cda59c09d
commit
bd069cc5e9
|
@ -3080,6 +3080,13 @@ void AP_AHRS::Log_Write()
|
|||
#if HAL_NAVEKF3_AVAILABLE
|
||||
EKF3.Log_Write();
|
||||
#endif
|
||||
|
||||
Write_AHRS2();
|
||||
Write_POS();
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
AP::sitl()->Log_Write_SIMSTATE();
|
||||
#endif
|
||||
}
|
||||
|
||||
// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed
|
||||
|
|
|
@ -427,7 +427,6 @@ public:
|
|||
|
||||
// Logging functions
|
||||
void Log_Write_Home_And_Origin();
|
||||
void Write_AHRS2(void) const;
|
||||
void Write_Attitude(const Vector3f &targets) const;
|
||||
|
||||
enum class LogOriginType {
|
||||
|
@ -435,7 +434,6 @@ public:
|
|||
ahrs_home = 1
|
||||
};
|
||||
void Write_Origin(LogOriginType origin_type, const Location &loc) const;
|
||||
void Write_POS(void) const;
|
||||
void write_video_stabilisation() const;
|
||||
|
||||
// return a smoothed and corrected gyro vector in radians/second
|
||||
|
@ -831,6 +829,11 @@ private:
|
|||
*/
|
||||
void copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results);
|
||||
|
||||
// write out secondary estimates:
|
||||
void Write_AHRS2(void) const;
|
||||
// write POS (canonical vehicle position) message out:
|
||||
void Write_POS(void) const;
|
||||
|
||||
#if HAL_NMEA_OUTPUT_ENABLED
|
||||
class AP_NMEA_Output* _nmea_out;
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue