mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: auto starts only when num cmds > 1
num_commands will be 1 when there is no mission because home counts as the first command
This commit is contained in:
parent
85b979ede9
commit
92738533fe
@ -20,7 +20,7 @@
|
||||
// auto_init - initialise auto controller
|
||||
static bool auto_init(bool ignore_checks)
|
||||
{
|
||||
if ((GPS_ok() && inertial_nav.position_ok() && mission.num_commands() > 0) || ignore_checks) {
|
||||
if ((GPS_ok() && inertial_nav.position_ok() && mission.num_commands() > 1) || ignore_checks) {
|
||||
// stop ROI from carrying over from previous runs of the mission
|
||||
// To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check
|
||||
if (auto_yaw_mode == AUTO_YAW_ROI) {
|
||||
|
Loading…
Reference in New Issue
Block a user