From 11e946eb54789cc9c115ac2f6fe5b5e9adc71cda Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sat, 18 Aug 2012 20:34:41 +0900 Subject: [PATCH] ArduCopter, ArduPilot: revert mavlink delay callback to be "unsigned long" --- ArduCopter/GCS_Mavlink.pde | 2 +- ArduPlane/GCS_Mavlink.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 15a087db90..0089118281 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1955,7 +1955,7 @@ GCS_MAVLINK::queued_waypoint_send() MAVLink to process packets while waiting for the initialisation to complete */ -static void mavlink_delay(uint32_t t) +static void mavlink_delay(unsigned long t) { uint32_t tstart; static uint32_t last_1hz, last_50hz, last_5s; diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 57506d40f1..b16e04acf9 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1963,7 +1963,7 @@ GCS_MAVLINK::queued_waypoint_send() MAVLink to process packets while waiting for the initialisation to complete */ -static void mavlink_delay(uint32_t t) +static void mavlink_delay(unsigned long t) { uint32_t tstart; static uint32_t last_1hz, last_50hz, last_5s;