Rover: fixes for new AP_Math location API

Pair-Programmed-With: Brandon Jones <brnjones@gmail.com>
This commit is contained in:
Andrew Tridgell 2013-08-05 10:18:29 +10:00
parent 0d36832b82
commit ee19b09e9f
4 changed files with 11 additions and 11 deletions

View File

@ -808,7 +808,7 @@ static void update_GPS(void)
} }
} }
have_position = ahrs.get_projected_position(&current_loc); have_position = ahrs.get_projected_position(current_loc);
if (g_gps->new_data && g_gps->status() >= GPS::GPS_OK_FIX_3D) { if (g_gps->new_data && g_gps->status() >= GPS::GPS_OK_FIX_3D) {
gps_fix_count++; gps_fix_count++;

View File

@ -121,9 +121,9 @@ static void set_next_WP(const struct Location *wp)
} }
// this is handy for the groundstation // this is handy for the groundstation
wp_totalDistance = get_distance(&current_loc, &next_WP); wp_totalDistance = get_distance(current_loc, next_WP);
wp_distance = wp_totalDistance; wp_distance = wp_totalDistance;
target_bearing = get_bearing_cd(&current_loc, &next_WP); target_bearing = get_bearing_cd(current_loc, next_WP);
nav_bearing = target_bearing; nav_bearing = target_bearing;
// set a new crosstrack bearing // set a new crosstrack bearing
@ -142,9 +142,9 @@ static void set_guided_WP(void)
next_WP = guided_WP; next_WP = guided_WP;
// this is handy for the groundstation // this is handy for the groundstation
wp_totalDistance = get_distance(&current_loc, &next_WP); wp_totalDistance = get_distance(current_loc, next_WP);
wp_distance = wp_totalDistance; wp_distance = wp_totalDistance;
target_bearing = get_bearing_cd(&current_loc, &next_WP); target_bearing = get_bearing_cd(current_loc, next_WP);
// set a new crosstrack bearing // set a new crosstrack bearing
// ---------------------------- // ----------------------------

View File

@ -216,7 +216,7 @@ static bool verify_nav_wp()
if ((wp_distance > 0) && (wp_distance <= g.waypoint_radius)) { if ((wp_distance > 0) && (wp_distance <= g.waypoint_radius)) {
gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"), gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"),
(unsigned)nav_command_index, (unsigned)nav_command_index,
(unsigned)get_distance(&current_loc, &next_WP)); (unsigned)get_distance(current_loc, next_WP));
return true; return true;
} }
@ -224,7 +224,7 @@ static bool verify_nav_wp()
if (location_passed_point(current_loc, prev_WP, next_WP)) { if (location_passed_point(current_loc, prev_WP, next_WP)) {
gcs_send_text_fmt(PSTR("Passed Waypoint #%i dist %um"), gcs_send_text_fmt(PSTR("Passed Waypoint #%i dist %um"),
(unsigned)nav_command_index, (unsigned)nav_command_index,
(unsigned)get_distance(&current_loc, &next_WP)); (unsigned)get_distance(current_loc, next_WP));
return true; return true;
} }
@ -242,7 +242,7 @@ static bool verify_RTL()
// have we gone past the waypoint? // have we gone past the waypoint?
if (location_passed_point(current_loc, prev_WP, next_WP)) { if (location_passed_point(current_loc, prev_WP, next_WP)) {
gcs_send_text_fmt(PSTR("Reached Home dist %um"), gcs_send_text_fmt(PSTR("Reached Home dist %um"),
(unsigned)get_distance(&current_loc, &next_WP)); (unsigned)get_distance(current_loc, next_WP));
return true; return true;
} }

View File

@ -17,7 +17,7 @@ static void navigate()
// waypoint distance from rover // waypoint distance from rover
// ---------------------------- // ----------------------------
wp_distance = get_distance(&current_loc, &next_WP); wp_distance = get_distance(current_loc, next_WP);
if (wp_distance < 0){ if (wp_distance < 0){
gcs_send_text_P(SEVERITY_HIGH,PSTR("<navigate> WP error - distance < 0")); gcs_send_text_P(SEVERITY_HIGH,PSTR("<navigate> WP error - distance < 0"));
@ -26,7 +26,7 @@ static void navigate()
// target_bearing is where we should be heading // target_bearing is where we should be heading
// -------------------------------------------- // --------------------------------------------
target_bearing = get_bearing_cd(&current_loc, &next_WP); target_bearing = get_bearing_cd(current_loc, next_WP);
// nav_bearing will includes xtrac correction // nav_bearing will includes xtrac correction
// ------------------------------------------ // ------------------------------------------
@ -61,7 +61,7 @@ static void update_crosstrack(void)
static void reset_crosstrack() static void reset_crosstrack()
{ {
crosstrack_bearing = get_bearing_cd(&prev_WP, &next_WP); // Used for track following crosstrack_bearing = get_bearing_cd(prev_WP, next_WP); // Used for track following
} }
void reached_waypoint() void reached_waypoint()