mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: remove HAL_CPU_CLASS_150 check, 150 is already a minimum requirement
This commit is contained in:
parent
c45b96fee9
commit
4e9d026448
|
@ -1,7 +1,5 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
// uncomment this to force the optimisation of this code, note that
|
||||
// this makes debugging harder
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
@ -962,4 +960,3 @@ bool SoloGimbalEKF::getStatus() const
|
|||
return YawAligned && (run_time > 15000);
|
||||
}
|
||||
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
|
Loading…
Reference in New Issue