Plane: use send_heartbeat wrapper

This commit is contained in:
Andrew Tridgell 2016-05-17 08:43:41 +10:00
parent a922b98ac0
commit 5b4bbf08fd
1 changed files with 4 additions and 7 deletions

View File

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