diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index b18cc8f32f..de39d2235d 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -93,13 +93,10 @@ void Plane::send_heartbeat(mavlink_channel_t chan) // indicate we have set a custom mode base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; - mavlink_msg_heartbeat_send( - chan, - MAV_TYPE_FIXED_WING, - MAV_AUTOPILOT_ARDUPILOTMEGA, - base_mode, - custom_mode, - system_status); + gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_FIXED_WING, + base_mode, + custom_mode, + system_status); } void Plane::send_attitude(mavlink_channel_t chan)