mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: remove redundant filter status checks
This commit is contained in:
parent
3641d3d508
commit
f1a6b06586
@ -20,7 +20,7 @@
|
||||
// auto_init - initialise auto controller
|
||||
static bool auto_init(bool ignore_checks)
|
||||
{
|
||||
if ((position_ok() && inertial_nav.get_filter_status().flags.horiz_pos_abs && mission.num_commands() > 1) || ignore_checks) {
|
||||
if ((position_ok() && mission.num_commands() > 1) || ignore_checks) {
|
||||
auto_mode = Auto_Loiter;
|
||||
|
||||
// stop ROI from carrying over from previous runs of the mission
|
||||
|
@ -7,7 +7,7 @@
|
||||
// circle_init - initialise circle controller flight mode
|
||||
static bool circle_init(bool ignore_checks)
|
||||
{
|
||||
if ((position_ok() && inertial_nav.get_filter_status().flags.horiz_pos_abs) || ignore_checks) {
|
||||
if (position_ok() || ignore_checks) {
|
||||
circle_pilot_yaw_override = false;
|
||||
|
||||
// initialize speeds and accelerations
|
||||
|
Loading…
Reference in New Issue
Block a user