Correctly fill armed field in heartbeat mavlink message

This commit is contained in:
Oleg Kalachev 2023-12-15 09:35:54 +03:00
parent 32d69cb4a0
commit f118bca6d1

View File

@ -21,7 +21,7 @@ void sendMavlink()
lastSlow = t;
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR,
MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_SAFETY_ARMED,
MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0,
0, MAV_STATE_STANDBY);
sendMessage(&msg);
}