mirror of https://github.com/ArduPilot/ardupilot
Plane: Remove some unneeded logging indirection
Saves 32 bytes on make px4-v2
This commit is contained in:
parent
53c66106d6
commit
b479f3760a
|
@ -147,7 +147,7 @@ void Plane::ahrs_update()
|
|||
ahrs.update();
|
||||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
Log_Write_IMU();
|
||||
DataFlash.Log_Write_IMU();
|
||||
}
|
||||
|
||||
// calculate a scaled roll limit based on current pitch
|
||||
|
@ -244,10 +244,10 @@ void Plane::update_logging1(void)
|
|||
}
|
||||
|
||||
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_IMU))
|
||||
Log_Write_IMU();
|
||||
DataFlash.Log_Write_IMU();
|
||||
|
||||
if (should_log(MASK_LOG_ATTITUDE_MED))
|
||||
Log_Write_AOA_SSA();
|
||||
DataFlash.Log_Write_AOA_SSA(ahrs);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -272,11 +272,6 @@ void Plane::Log_Write_AETR()
|
|||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void Plane::Log_Write_IMU()
|
||||
{
|
||||
DataFlash.Log_Write_IMU();
|
||||
}
|
||||
|
||||
void Plane::Log_Write_RC(void)
|
||||
{
|
||||
DataFlash.Log_Write_RCIN();
|
||||
|
@ -287,18 +282,6 @@ void Plane::Log_Write_RC(void)
|
|||
Log_Write_AETR();
|
||||
}
|
||||
|
||||
// Write a AIRSPEED packet
|
||||
void Plane::Log_Write_Airspeed(void)
|
||||
{
|
||||
DataFlash.Log_Write_Airspeed(airspeed);
|
||||
}
|
||||
|
||||
// Write a AOA and SSA packet
|
||||
void Plane::Log_Write_AOA_SSA(void)
|
||||
{
|
||||
DataFlash.Log_Write_AOA_SSA(ahrs);
|
||||
}
|
||||
|
||||
// log ahrs home and EKF origin to dataflash
|
||||
void Plane::Log_Write_Home_And_Origin()
|
||||
{
|
||||
|
@ -375,7 +358,6 @@ void Plane::log_init(void)
|
|||
|
||||
#else // LOGGING_ENABLED
|
||||
|
||||
void Plane::Log_Write_AOA_SSA(void) {}
|
||||
void Plane::Log_Write_Attitude(void) {}
|
||||
void Plane::Log_Write_Fast(void) {}
|
||||
void Plane::Log_Write_Performance() {}
|
||||
|
@ -390,9 +372,7 @@ void Plane::Log_Write_Optflow() {}
|
|||
#endif
|
||||
|
||||
void Plane::Log_Arm_Disarm() {}
|
||||
void Plane::Log_Write_IMU() {}
|
||||
void Plane::Log_Write_RC(void) {}
|
||||
void Plane::Log_Write_Airspeed(void) {}
|
||||
void Plane::Log_Write_Home_And_Origin() {}
|
||||
void Plane::Log_Write_Vehicle_Startup_Messages() {}
|
||||
|
||||
|
|
|
@ -800,9 +800,7 @@ private:
|
|||
void Log_Write_Sonar();
|
||||
void Log_Write_Optflow();
|
||||
void Log_Arm_Disarm();
|
||||
void Log_Write_IMU();
|
||||
void Log_Write_RC(void);
|
||||
void Log_Write_Airspeed(void);
|
||||
void Log_Write_Home_And_Origin();
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void Log_Write_AOA_SSA();
|
||||
|
|
|
@ -73,7 +73,7 @@ void Plane::read_airspeed(void)
|
|||
if (airspeed.enabled()) {
|
||||
airspeed.read();
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
Log_Write_Airspeed();
|
||||
DataFlash.Log_Write_Airspeed(airspeed);
|
||||
}
|
||||
|
||||
// supply a new temperature to the barometer from the digital
|
||||
|
|
Loading…
Reference in New Issue