Plane: Climb/descent "intent" param with CONTINUE_AND_CHANGE_ALT

Param 1 of CONTINUE_AND_CHANGE_ALT now denotes which direction the
user expects the plane to travel when changing altitude:

0 = no expectation, command completes when within 5 m of altitude.
1 = climb expected, command completes at or above altitude.
2 = descent expected, command completes at or below altitude.
This commit is contained in:
Michael Day 2015-08-18 20:48:13 -06:00 committed by Grant Morphett
parent 7e8e3698ae
commit eea9f13871
1 changed files with 12 additions and 1 deletions

View File

@ -376,6 +376,7 @@ void Plane::do_loiter_time(const AP_Mission::Mission_Command& cmd)
void Plane::do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd)
{
next_WP_loc.alt = cmd.content.location.alt + home.alt;
condition_value = cmd.p1;
reset_offset_altitude();
}
@ -643,7 +644,17 @@ bool Plane::verify_RTL()
bool Plane::verify_continue_and_change_alt()
{
if (abs(adjusted_altitude_cm() - next_WP_loc.alt) <= 500) {
//climbing?
if (condition_value == 1 && adjusted_altitude_cm() >= next_WP_loc.alt) {
return true;
}
//descending?
else if (condition_value == 2 &&
adjusted_altitude_cm() <= next_WP_loc.alt) {
return true;
}
//don't care if we're climbing or descending
else if (abs(adjusted_altitude_cm() - next_WP_loc.alt) <= 500) {
return true;
}