Rover: remove next_WP, wp_distance, navigate

Also remove prev_WP, wp_totalDistance which are all handled within mode class
This commit is contained in:
Randy Mackay 2017-08-03 10:37:29 +09:00
parent b4af441eb9
commit fe6465b748
4 changed files with 0 additions and 38 deletions

View File

@ -308,12 +308,6 @@ private:
uint32_t control_sensors_enabled; uint32_t control_sensors_enabled;
uint32_t control_sensors_health; 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 // Conditional command
// A value used in condition commands (eg delay, change alt, etc.) // 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. // 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 // true if the compass's initial location has been set
bool compass_init_location; 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 // IMU variables
// The main loop execution time. Seconds // The main loop execution time. Seconds
// This is the time between calls to the DCM algorithm and is the Integration time for the gyros. // This is the time between calls to the DCM algorithm and is the Integration time for the gyros.

View File

@ -56,9 +56,6 @@ bool Rover::set_home(const Location& loc, bool lock)
DataFlash.Log_Write_Mission_Cmd(mission, temp_cmd); DataFlash.Log_Write_Mission_Cmd(mission, temp_cmd);
} }
} }
// initialise navigation to home
next_WP = prev_WP = home;
} }
// lock home position // lock home position

View File

@ -76,7 +76,6 @@ void Rover::read_control_switch()
} }
oldSwitchPosition = switchPosition; oldSwitchPosition = switchPosition;
prev_WP = current_loc;
// reset speed integrator // reset speed integrator
g.pidSpeedThrottle.reset_I(); g.pidSpeedThrottle.reset_I();

View File

@ -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);
}