mirror of https://github.com/ArduPilot/ardupilot
AC_AutoTune: add and use header guards
This commit is contained in:
parent
c93fd0b534
commit
e95b1e5dd3
|
@ -1,3 +1,7 @@
|
|||
#include "AC_AutoTune_config.h"
|
||||
|
||||
#if AC_AUTOTUNE_ENABLED
|
||||
|
||||
#include "AC_AutoTune.h"
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
@ -757,3 +761,4 @@ void AC_AutoTune::next_tune_type(TuneType &curr_tune_type, bool reset)
|
|||
curr_tune_type = tune_seq[tune_seq_curr];
|
||||
}
|
||||
|
||||
#endif // AC_AUTOTUNE_ENABLED
|
||||
|
|
|
@ -18,6 +18,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AC_AutoTune_config.h"
|
||||
|
||||
#if AC_AUTOTUNE_ENABLED
|
||||
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl.h>
|
||||
#include <AC_AttitudeControl/AC_PosControl.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
@ -327,3 +331,5 @@ private:
|
|||
uint32_t last_pilot_override_warning;
|
||||
|
||||
};
|
||||
|
||||
#endif // AC_AUTOTUNE_ENABLED
|
||||
|
|
|
@ -17,6 +17,10 @@
|
|||
Converted to a library by Andrew Tridgell, and rewritten to include helicopters by Bill Geyer
|
||||
*/
|
||||
|
||||
#include "AC_AutoTune_config.h"
|
||||
|
||||
#if AC_AUTOTUNE_ENABLED
|
||||
|
||||
#include "AC_AutoTune_Heli.h"
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
@ -1941,3 +1945,5 @@ bool AC_AutoTune_Heli::exceeded_freq_range(float frequency)
|
|||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif // AC_AUTOTUNE_ENABLED
|
||||
|
|
|
@ -18,6 +18,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AC_AutoTune_config.h"
|
||||
|
||||
#if AC_AUTOTUNE_ENABLED
|
||||
|
||||
#include "AC_AutoTune.h"
|
||||
#include <AP_Math/chirp.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
@ -296,3 +300,5 @@ private:
|
|||
|
||||
Chirp chirp_input;
|
||||
};
|
||||
|
||||
#endif // AC_AUTOTUNE_ENABLED
|
||||
|
|
|
@ -1,3 +1,7 @@
|
|||
#include "AC_AutoTune_config.h"
|
||||
|
||||
#if AC_AUTOTUNE_ENABLED
|
||||
|
||||
#include "AC_AutoTune_Multi.h"
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
@ -1246,3 +1250,5 @@ uint32_t AC_AutoTune_Multi::get_testing_step_timeout_ms() const
|
|||
return AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
|
||||
}
|
||||
|
||||
|
||||
#endif // AC_AUTOTUNE_ENABLED
|
||||
|
|
|
@ -19,6 +19,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AC_AutoTune_config.h"
|
||||
|
||||
#if AC_AUTOTUNE_ENABLED
|
||||
|
||||
#include "AC_AutoTune.h"
|
||||
|
||||
class AC_AutoTune_Multi : public AC_AutoTune
|
||||
|
@ -168,3 +172,5 @@ private:
|
|||
AP_Float aggressiveness; // aircraft response aggressiveness to be tuned
|
||||
AP_Float min_d; // minimum rate d gain allowed during tuning
|
||||
};
|
||||
|
||||
#endif // AC_AUTOTUNE_ENABLED
|
||||
|
|
|
@ -0,0 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AC_AUTOTUNE_ENABLED
|
||||
#define AC_AUTOTUNE_ENABLED 1
|
||||
#endif
|
Loading…
Reference in New Issue