Pass mode to heartbeat

This commit is contained in:
Oleg Kalachev 2025-07-22 13:52:45 +03:00
parent 41f1661231
commit a9ede4c90f

View File

@ -37,7 +37,7 @@ void sendMavlink() {
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (armed * MAV_MODE_FLAG_SAFETY_ARMED) | ((mode == STAB) * MAV_MODE_FLAG_STABILIZE_ENABLED),
0, MAV_STATE_STANDBY);
mode, MAV_STATE_STANDBY);
sendMessage(&msg);
mavlink_msg_extended_sys_state_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,