diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index ee3faa4c26..77487f2d51 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -32,7 +32,6 @@ Rover::Rover(void) : modes(&g.mode1), nav_controller(&L1_controller), control_mode(&mode_initializing), - home(ahrs.get_home()), G_Dt(0.02f) { } diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index fef860252b..194d9648b1 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -297,11 +297,6 @@ private: FUNCTOR_BIND_MEMBER(&Rover::handle_battery_failsafe, void, const char*, const int8_t), _failsafe_priorities}; - // 3D Location vectors - // Location structure defined in AP_Common - // The home location used for RTL. The location is set when we first get stable GPS lock - const struct Location &home; - // true if the compass's initial location has been set bool compass_init_location;