Copter: fix MISSION_START support
Vehicle must already be armed Set auto-armed to true to allow take-off without pilot raising throttle
This commit is contained in:
parent
15fe925974
commit
9ac892acea
@ -1149,7 +1149,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
|
||||
case MAV_CMD_MISSION_START:
|
||||
if (set_mode(AUTO)) {
|
||||
if (motors.armed() && set_mode(AUTO)) {
|
||||
set_auto_armed(true);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user