From 01caa7388aace6e7ec019606c9ee4bda9d9391ef Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 May 2016 08:36:59 +1000 Subject: [PATCH] Rover: use send_heartbeat() wrapper --- APMrover2/GCS_Mavlink.cpp | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 925342aeaa..e8147e95c9 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -66,13 +66,10 @@ void Rover::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_GROUND_ROVER, - MAV_AUTOPILOT_ARDUPILOTMEGA, - base_mode, - custom_mode, - system_status); + gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_GROUND_ROVER, + base_mode, + custom_mode, + system_status); } void Rover::send_attitude(mavlink_channel_t chan)