mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: fixes for updated AP_Math and AHRS APIs
Pair-Programmed-With: Brandon Jones <brnjones@gmail.com>
This commit is contained in:
parent
086c7d70d8
commit
a33573352e
@ -987,7 +987,7 @@ static void update_GPS(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// get position from AHRS
|
// get position from AHRS
|
||||||
have_position = ahrs.get_position(¤t_loc);
|
have_position = ahrs.get_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) {
|
||||||
g_gps->new_data = false;
|
g_gps->new_data = false;
|
||||||
|
@ -393,7 +393,7 @@ static bool verify_nav_wp()
|
|||||||
if (wp_distance <= nav_controller->turn_distance(g.waypoint_radius)) {
|
if (wp_distance <= nav_controller->turn_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(¤t_loc, &next_WP));
|
(unsigned)get_distance(current_loc, next_WP));
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -401,7 +401,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(¤t_loc, &next_WP));
|
(unsigned)get_distance(current_loc, next_WP));
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -213,7 +213,7 @@ static void geofence_check(bool altitude_check_only)
|
|||||||
} else if (geofence_check_maxalt()) {
|
} else if (geofence_check_maxalt()) {
|
||||||
outside = true;
|
outside = true;
|
||||||
breach_type = FENCE_BREACH_MAXALT;
|
breach_type = FENCE_BREACH_MAXALT;
|
||||||
} else if (!altitude_check_only && ahrs.get_position(&loc)) {
|
} else if (!altitude_check_only && ahrs.get_position(loc)) {
|
||||||
Vector2l location;
|
Vector2l location;
|
||||||
location.x = loc.lat;
|
location.x = loc.lat;
|
||||||
location.y = loc.lng;
|
location.y = loc.lng;
|
||||||
|
@ -60,7 +60,7 @@ static void navigate()
|
|||||||
|
|
||||||
// waypoint distance from plane
|
// waypoint distance from plane
|
||||||
// ----------------------------
|
// ----------------------------
|
||||||
wp_distance = get_distance(¤t_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("WP error - distance < 0"));
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("WP error - distance < 0"));
|
||||||
@ -186,9 +186,9 @@ static void update_cruise()
|
|||||||
if (cruise_state.locked_heading) {
|
if (cruise_state.locked_heading) {
|
||||||
next_WP = prev_WP;
|
next_WP = prev_WP;
|
||||||
// always look 1km ahead
|
// always look 1km ahead
|
||||||
location_update(&next_WP,
|
location_update(next_WP,
|
||||||
cruise_state.locked_heading_cd*0.01f,
|
cruise_state.locked_heading_cd*0.01f,
|
||||||
get_distance(&prev_WP, ¤t_loc) + 1000);
|
get_distance(prev_WP, current_loc) + 1000);
|
||||||
nav_controller->update_waypoint(prev_WP, next_WP);
|
nav_controller->update_waypoint(prev_WP, next_WP);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -233,7 +233,7 @@ static void setup_glide_slope(void)
|
|||||||
{
|
{
|
||||||
// establish the distance we are travelling to the next waypoint,
|
// establish the distance we are travelling to the next waypoint,
|
||||||
// for calculating out rate of change of altitude
|
// for calculating out rate of change of altitude
|
||||||
wp_totalDistance = get_distance(¤t_loc, &next_WP);
|
wp_totalDistance = get_distance(current_loc, next_WP);
|
||||||
wp_distance = wp_totalDistance;
|
wp_distance = wp_totalDistance;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user