mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Plane: Baro does its own dataflash logging
This commit is contained in:
parent
63e8fffbe4
commit
2b54113334
@ -861,9 +861,6 @@ void Plane::set_flight_stage(AP_Vehicle::FixedWing::FlightStage fs)
|
||||
void Plane::update_alt()
|
||||
{
|
||||
barometer.update();
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
Log_Write_Baro();
|
||||
}
|
||||
|
||||
// calculate the sink rate.
|
||||
float sink_rate;
|
||||
|
@ -294,13 +294,6 @@ void Plane::Log_Write_RC(void)
|
||||
Log_Write_AETR();
|
||||
}
|
||||
|
||||
void Plane::Log_Write_Baro(void)
|
||||
{
|
||||
if (!ahrs.have_ekf_logging()) {
|
||||
DataFlash.Log_Write_Baro();
|
||||
}
|
||||
}
|
||||
|
||||
// Write a AIRSPEED packet
|
||||
void Plane::Log_Write_Airspeed(void)
|
||||
{
|
||||
@ -406,7 +399,6 @@ void Plane::Log_Arm_Disarm() {}
|
||||
void Plane::Log_Write_GPS(uint8_t instance) {}
|
||||
void Plane::Log_Write_IMU() {}
|
||||
void Plane::Log_Write_RC(void) {}
|
||||
void Plane::Log_Write_Baro(void) {}
|
||||
void Plane::Log_Write_Airspeed(void) {}
|
||||
void Plane::Log_Write_Home_And_Origin() {}
|
||||
|
||||
|
@ -815,7 +815,6 @@ private:
|
||||
void Log_Write_GPS(uint8_t instance);
|
||||
void Log_Write_IMU();
|
||||
void Log_Write_RC(void);
|
||||
void Log_Write_Baro(void);
|
||||
void Log_Write_Airspeed(void);
|
||||
void Log_Write_Home_And_Origin();
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
|
@ -587,6 +587,7 @@ void Plane::startup_INS_ground(void)
|
||||
|
||||
// read Baro pressure at ground
|
||||
//-----------------------------
|
||||
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||
barometer.calibrate();
|
||||
|
||||
if (airspeed.enabled()) {
|
||||
|
Loading…
Reference in New Issue
Block a user