Browse Source

ArduCopter, ArduPilot: revert mavlink delay callback to be "unsigned long"

master
rmackay9 13 years ago
parent
commit
11e946eb54
  1. 2
      ArduCopter/GCS_Mavlink.pde
  2. 2
      ArduPlane/GCS_Mavlink.pde

2
ArduCopter/GCS_Mavlink.pde

@ -1955,7 +1955,7 @@ GCS_MAVLINK::queued_waypoint_send() @@ -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;

2
ArduPlane/GCS_Mavlink.pde

@ -1963,7 +1963,7 @@ GCS_MAVLINK::queued_waypoint_send() @@ -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;

Loading…
Cancel
Save