mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: adjust for Location_Class and Location unification
This commit is contained in:
parent
384ab476b4
commit
30980815a8
|
@ -1341,7 +1341,7 @@ void AP_GPS::calc_blended_state(void)
|
||||||
state[GPS_BLENDED_INSTANCE].have_speed_accuracy = false;
|
state[GPS_BLENDED_INSTANCE].have_speed_accuracy = false;
|
||||||
state[GPS_BLENDED_INSTANCE].have_horizontal_accuracy = false;
|
state[GPS_BLENDED_INSTANCE].have_horizontal_accuracy = false;
|
||||||
state[GPS_BLENDED_INSTANCE].have_vertical_accuracy = false;
|
state[GPS_BLENDED_INSTANCE].have_vertical_accuracy = false;
|
||||||
memset(&state[GPS_BLENDED_INSTANCE].location, 0, sizeof(state[GPS_BLENDED_INSTANCE].location));
|
state[GPS_BLENDED_INSTANCE].location = {};
|
||||||
|
|
||||||
_blended_antenna_offset.zero();
|
_blended_antenna_offset.zero();
|
||||||
_blended_lag_sec = 0;
|
_blended_lag_sec = 0;
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
|
|
Loading…
Reference in New Issue