mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Plane: fixed arming bit in MAVLink heartbeat message
This commit is contained in:
parent
24658197ff
commit
b0236610b2
@ -91,7 +91,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
||||
#endif
|
||||
|
||||
// we are armed if we are not initialising
|
||||
if (control_mode != INITIALISING) {
|
||||
if (control_mode != INITIALISING && arming.is_armed()) {
|
||||
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user