mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Landing: Implement is_on_approach for deepstall
(Fixes a disarm in flight)
This commit is contained in:
parent
126d5ce5d4
commit
338d745de1
@ -308,6 +308,7 @@ bool AP_Landing::is_on_approach(void) const
|
||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||
return type_slope_is_on_approach();
|
||||
case TYPE_DEEPSTALL:
|
||||
return deepstall.is_on_approach();
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
@ -367,6 +367,11 @@ bool AP_Landing_Deepstall::is_flying_forward(void) const
|
||||
return stage != DEEPSTALL_STAGE_LAND;
|
||||
}
|
||||
|
||||
bool AP_Landing_Deepstall::is_on_approach(void) const
|
||||
{
|
||||
return stage == DEEPSTALL_STAGE_LAND;
|
||||
}
|
||||
|
||||
bool AP_Landing_Deepstall::get_target_altitude_location(Location &location)
|
||||
{
|
||||
memcpy(&location, &landing_point, sizeof(Location));
|
||||
|
@ -102,6 +102,7 @@ private:
|
||||
int32_t get_target_airspeed_cm(void) const;
|
||||
bool is_throttle_suppressed(void) const;
|
||||
bool is_flying_forward(void) const;
|
||||
bool is_on_approach(void) const;
|
||||
bool terminate(void);
|
||||
void log(void) const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user