From b4af441eb946edc52bd8462126c9e077ade0f871 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 3 Aug 2017 10:34:43 +0900 Subject: [PATCH] Rover: remove unused update_navigation --- APMrover2/APMrover2.cpp | 5 ----- APMrover2/Rover.h | 1 - APMrover2/navigation.cpp | 4 ---- 3 files changed, 10 deletions(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index eeb230d8a5..555495d4c8 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -408,9 +408,4 @@ void Rover::update_current_mode(void) control_mode->update(); } -void Rover::update_navigation() -{ - control_mode->update_navigation(); -} - AP_HAL_MAIN_CALLBACKS(&rover); diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index f50891518e..8c724f8fad 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -431,7 +431,6 @@ private: void update_GPS_50Hz(void); void update_GPS_10Hz(void); void update_current_mode(void); - void update_navigation(); void send_heartbeat(mavlink_channel_t chan); void send_attitude(mavlink_channel_t chan); void update_sensor_status_flags(void); diff --git a/APMrover2/navigation.cpp b/APMrover2/navigation.cpp index 9a8d4c84a4..8d7e6d5d0b 100644 --- a/APMrover2/navigation.cpp +++ b/APMrover2/navigation.cpp @@ -18,10 +18,6 @@ void Rover::navigate() // waypoint distance from rover // ---------------------------- wp_distance = get_distance(current_loc, next_WP); - - // control mode specific updates to nav_bearing - // -------------------------------------------- - update_navigation(); }