mirror of https://github.com/ArduPilot/ardupilot
parent
ba312ee68e
commit
262f8b9f48
|
@ -41,6 +41,9 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
|||
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
||||
break;
|
||||
|
||||
case STOP:
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED |
|
||||
MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||
|
|
|
@ -55,6 +55,7 @@
|
|||
|
||||
enum ControlMode {
|
||||
MANUAL=0,
|
||||
STOP=1,
|
||||
AUTO=10,
|
||||
INITIALISING=16
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue