diff --git a/flix/mavlink.ino b/flix/mavlink.ino index 44e7005..758c90f 100644 --- a/flix/mavlink.ino +++ b/flix/mavlink.ino @@ -28,7 +28,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 | armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0, + MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0), 0, MAV_STATE_STANDBY); sendMessage(&msg); } diff --git a/flix/wifi.ino b/flix/wifi.ino index 562610e..3572421 100644 --- a/flix/wifi.ino +++ b/flix/wifi.ino @@ -24,7 +24,6 @@ void setupWiFi() { } void sendWiFi(const uint8_t *buf, int len) { -// if (!udp.beginPacket(WIFI_UDP_IP, WIFI_UDP_PORT)) return; udp.beginPacket(WIFI_UDP_IP, WIFI_UDP_PORT); udp.write(buf, len); udp.endPacket();