mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: add optflow_position_ok and use for loiter
This allows entering Loiter flight mode with only optical flow based position
This commit is contained in:
parent
199dc3454d
commit
fd0b82f669
@ -7,7 +7,7 @@
|
||||
// loiter_init - initialise loiter controller
|
||||
static bool loiter_init(bool ignore_checks)
|
||||
{
|
||||
if (position_ok() || ignore_checks) {
|
||||
if (position_ok() || optflow_position_ok() || ignore_checks) {
|
||||
|
||||
// set target to current position
|
||||
wp_nav.init_loiter_target();
|
||||
|
@ -349,6 +349,22 @@ static bool position_ok()
|
||||
}
|
||||
}
|
||||
|
||||
// optflow_position_ok - returns true if optical flow based position estimate is ok
|
||||
static bool optflow_position_ok()
|
||||
{
|
||||
#if OPTFLOW != ENABLED
|
||||
return false;
|
||||
#else
|
||||
// return immediately if optflow is not enabled
|
||||
if (!optflow.enabled()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// get filter status from inertial nav or EKF
|
||||
return inertial_nav.get_filter_status().flags.horiz_pos_rel;
|
||||
#endif
|
||||
}
|
||||
|
||||
// update_auto_armed - update status of auto_armed flag
|
||||
static void update_auto_armed()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user