mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: use AP_CheckFirmware
This commit is contained in:
parent
92cb78dfe7
commit
e217c1c82f
|
@ -8,6 +8,7 @@
|
||||||
#include <AP_OSD/AP_OSD.h>
|
#include <AP_OSD/AP_OSD.h>
|
||||||
#include <AP_RPM/AP_RPM.h>
|
#include <AP_RPM/AP_RPM.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
|
#include <AP_CheckFirmware/AP_CheckFirmware.h>
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
#include <AP_HAL_ChibiOS/sdcard.h>
|
#include <AP_HAL_ChibiOS/sdcard.h>
|
||||||
#endif
|
#endif
|
||||||
|
@ -107,6 +108,10 @@ void AP_Vehicle::setup()
|
||||||
AP::fwversion().fw_string,
|
AP::fwversion().fw_string,
|
||||||
(unsigned)hal.util->available_memory());
|
(unsigned)hal.util->available_memory());
|
||||||
|
|
||||||
|
#if AP_CHECK_FIRMWARE_ENABLED
|
||||||
|
check_firmware_print();
|
||||||
|
#endif
|
||||||
|
|
||||||
load_parameters();
|
load_parameters();
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
|
|
@ -51,6 +51,7 @@
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
#endif
|
#endif
|
||||||
|
#include <AP_CheckFirmware/AP_CheckFirmware.h>
|
||||||
|
|
||||||
class AP_Vehicle : public AP_HAL::HAL::Callbacks {
|
class AP_Vehicle : public AP_HAL::HAL::Callbacks {
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue