AP_InertialSensor: fix INS_generic example (call BoardConfig.init())

This commit is contained in:
Peter Barker 2016-10-24 11:50:44 +11:00 committed by Randy Mackay
parent d61775226f
commit 17883f6683

View File

@ -5,6 +5,7 @@
// //
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_InertialSensor/AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
const AP_HAL::HAL &hal = AP_HAL::get_HAL(); const AP_HAL::HAL &hal = AP_HAL::get_HAL();
@ -14,8 +15,14 @@ AP_InertialSensor ins;
static void display_offsets_and_scaling(); static void display_offsets_and_scaling();
static void run_test(); static void run_test();
// board specific config
AP_BoardConfig BoardConfig;
void setup(void) void setup(void)
{ {
// setup any board specific drivers
BoardConfig.init();
hal.console->println("AP_InertialSensor startup..."); hal.console->println("AP_InertialSensor startup...");
ins.init(100); ins.init(100);