ArduCopter: handle renaming of AP_InertialNav_NavEKF to AP_InertialNav
This commit is contained in:
parent
cf9f060db8
commit
a88264d73b
@ -50,7 +50,7 @@
|
|||||||
#include <Filter/Filter.h> // Filter library
|
#include <Filter/Filter.h> // Filter library
|
||||||
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
|
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
|
||||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||||
#include <AP_InertialNav/AP_InertialNav_NavEKF.h> // ArduPilot Mega inertial navigation library
|
#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
|
||||||
#include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
|
#include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
|
||||||
#include <AC_WPNav/AC_Loiter.h> // ArduCopter Loiter Mode Library
|
#include <AC_WPNav/AC_Loiter.h> // ArduCopter Loiter Mode Library
|
||||||
#include <AC_WPNav/AC_Circle.h> // circle navigation library
|
#include <AC_WPNav/AC_Circle.h> // circle navigation library
|
||||||
@ -447,7 +447,7 @@ private:
|
|||||||
Location current_loc;
|
Location current_loc;
|
||||||
|
|
||||||
// Inertial Navigation
|
// Inertial Navigation
|
||||||
AP_InertialNav_NavEKF inertial_nav;
|
AP_InertialNav inertial_nav;
|
||||||
|
|
||||||
// Attitude, Position and Waypoint navigation objects
|
// Attitude, Position and Waypoint navigation objects
|
||||||
// To-Do: move inertial nav up or other navigation variables down here
|
// To-Do: move inertial nav up or other navigation variables down here
|
||||||
|
Loading…
Reference in New Issue
Block a user