AP_InertialNav: fixed example build

This commit is contained in:
Andrew Tridgell 2014-03-24 12:03:47 +11:00
parent 1b1a92251f
commit 271ba3a6bc

View File

@ -59,7 +59,7 @@ void setup(void)
hal.console->println_P(PSTR("AP_InertialNav test startup..."));
gps = &auto_gps;
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G);
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G, NULL);
ins.init(AP_InertialSensor::COLD_START,
AP_InertialSensor::RATE_100HZ);