2012-04-30 04:17:14 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2015-05-13 00:16:45 -03:00
|
|
|
#include "Rover.h"
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
//****************************************************************
|
|
|
|
// Function that will calculate the desired direction to fly and distance
|
|
|
|
//****************************************************************
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::navigate()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
|
|
|
// do not navigate with corrupt data
|
|
|
|
// ---------------------------------
|
2012-11-28 07:44:03 -04:00
|
|
|
if (!have_position) {
|
2012-04-30 04:17:14 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-10-30 02:41:06 -03:00
|
|
|
if ((next_WP.lat == 0) || (home_is_set==HOME_UNSET)){
|
2012-04-30 04:17:14 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-03-01 07:32:57 -04:00
|
|
|
// waypoint distance from rover
|
2012-04-30 04:17:14 -03:00
|
|
|
// ----------------------------
|
2014-03-17 04:44:25 -03:00
|
|
|
wp_distance = get_distance(current_loc, next_WP);
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
// control mode specific updates to nav_bearing
|
|
|
|
// --------------------------------------------
|
|
|
|
update_navigation();
|
|
|
|
}
|
|
|
|
|
|
|
|
|