diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 7e6dfbb8dd..0e3517c4d6 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -406,12 +406,6 @@ void Copter::notify_flight_mode() { notify.set_flight_mode_str(flightmode->name4()); } -void Mode::update_navigation() -{ - // run autopilot to make high level decisions about control modes - run_autopilot(); -} - // get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle // returns desired angle in centi-degrees void Mode::get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index dc8e40ca55..7516268029 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -77,8 +77,6 @@ public: virtual uint32_t wp_distance() const { return 0; } virtual float crosstrack_error() const { return 0.0f;} - void update_navigation(); - int32_t get_alt_above_ground_cm(void); // pilot input processing @@ -98,9 +96,6 @@ public: protected: - // navigation support functions - virtual void run_autopilot() {} - // helper functions bool is_disarmed_or_landed() const; void zero_throttle_and_relax_ac(bool spool_up = false); diff --git a/ArduCopter/navigation.cpp b/ArduCopter/navigation.cpp index 4d209a0788..1cc66f2744 100644 --- a/ArduCopter/navigation.cpp +++ b/ArduCopter/navigation.cpp @@ -6,8 +6,6 @@ void Copter::run_nav_updates(void) { update_super_simple_bearing(false); - - flightmode->update_navigation(); } // distance between vehicle and home in cm