From fe6465b748e5bb91e9481e9f748a6db5beed79a0 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 3 Aug 2017 10:37:29 +0900 Subject: [PATCH] Rover: remove next_WP, wp_distance, navigate Also remove prev_WP, wp_totalDistance which are all handled within mode class --- APMrover2/Rover.h | 11 ----------- APMrover2/commands.cpp | 3 --- APMrover2/control_modes.cpp | 1 - APMrover2/navigation.cpp | 23 ----------------------- 4 files changed, 38 deletions(-) delete mode 100644 APMrover2/navigation.cpp diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 8c724f8fad..9991343659 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -308,12 +308,6 @@ private: uint32_t control_sensors_enabled; uint32_t control_sensors_health; - // Waypoint distances - // Distance between rover and next waypoint. Meters - float wp_distance; - // Distance between previous and next waypoint. Meters - int32_t wp_totalDistance; - // Conditional command // A value used in condition commands (eg delay, change alt, etc.) // For example in a change altitude command, it is the altitude to change to. @@ -336,11 +330,6 @@ private: // true if the compass's initial location has been set bool compass_init_location; - // The location of the previous waypoint. Used for track following and altitude ramp calculations - struct Location prev_WP; - // The location of the current/active waypoint. Used for track following - struct Location next_WP; - // IMU variables // The main loop execution time. Seconds // This is the time between calls to the DCM algorithm and is the Integration time for the gyros. diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index 2e3d2042d7..6761ddb741 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -56,9 +56,6 @@ bool Rover::set_home(const Location& loc, bool lock) DataFlash.Log_Write_Mission_Cmd(mission, temp_cmd); } } - - // initialise navigation to home - next_WP = prev_WP = home; } // lock home position diff --git a/APMrover2/control_modes.cpp b/APMrover2/control_modes.cpp index c442b821d4..85bd340a54 100644 --- a/APMrover2/control_modes.cpp +++ b/APMrover2/control_modes.cpp @@ -76,7 +76,6 @@ void Rover::read_control_switch() } oldSwitchPosition = switchPosition; - prev_WP = current_loc; // reset speed integrator g.pidSpeedThrottle.reset_I(); diff --git a/APMrover2/navigation.cpp b/APMrover2/navigation.cpp deleted file mode 100644 index 8d7e6d5d0b..0000000000 --- a/APMrover2/navigation.cpp +++ /dev/null @@ -1,23 +0,0 @@ -#include "Rover.h" - -//**************************************************************** -// Function that will calculate the desired direction to fly and distance -//**************************************************************** -void Rover::navigate() -{ - // do not navigate with corrupt data - // --------------------------------- - if (!have_position) { - return; - } - - if ((next_WP.lat == 0 && next_WP.lng == 0) || (home_is_set == HOME_UNSET)) { - return; - } - - // waypoint distance from rover - // ---------------------------- - wp_distance = get_distance(current_loc, next_WP); -} - -