mirror of https://github.com/ArduPilot/ardupilot
Copter: position_ok when optical flow ok
Previously the GPS based absolute position was required This allows using optical flow in all flight modes
This commit is contained in:
parent
b068f51c45
commit
9b80ab18ae
|
@ -9,7 +9,7 @@
|
||||||
// brake_init - initialise brake controller
|
// brake_init - initialise brake controller
|
||||||
bool Copter::brake_init(bool ignore_checks)
|
bool Copter::brake_init(bool ignore_checks)
|
||||||
{
|
{
|
||||||
if (position_ok() || optflow_position_ok() || ignore_checks) {
|
if (position_ok() || ignore_checks) {
|
||||||
|
|
||||||
// set desired acceleration to zero
|
// set desired acceleration to zero
|
||||||
wp_nav.clear_pilot_desired_acceleration();
|
wp_nav.clear_pilot_desired_acceleration();
|
||||||
|
|
|
@ -9,7 +9,7 @@
|
||||||
// loiter_init - initialise loiter controller
|
// loiter_init - initialise loiter controller
|
||||||
bool Copter::loiter_init(bool ignore_checks)
|
bool Copter::loiter_init(bool ignore_checks)
|
||||||
{
|
{
|
||||||
if (position_ok() || optflow_position_ok() || ignore_checks) {
|
if (position_ok() || ignore_checks) {
|
||||||
|
|
||||||
// set target to current position
|
// set target to current position
|
||||||
wp_nav.init_loiter_target();
|
wp_nav.init_loiter_target();
|
||||||
|
|
|
@ -329,7 +329,7 @@ bool Copter::position_ok()
|
||||||
}
|
}
|
||||||
|
|
||||||
// check ekf position estimate
|
// check ekf position estimate
|
||||||
return ekf_position_ok();
|
return (ekf_position_ok() || optflow_position_ok());
|
||||||
}
|
}
|
||||||
|
|
||||||
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
|
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
|
||||||
|
|
Loading…
Reference in New Issue