ArduCopter, ArduPilot: revert mavlink delay callback to be "unsigned long"
This commit is contained in:
parent
9f81d0c601
commit
b80a3943aa
@ -1955,7 +1955,7 @@ GCS_MAVLINK::queued_waypoint_send()
|
|||||||
MAVLink to process packets while waiting for the initialisation to
|
MAVLink to process packets while waiting for the initialisation to
|
||||||
complete
|
complete
|
||||||
*/
|
*/
|
||||||
static void mavlink_delay(uint32_t t)
|
static void mavlink_delay(unsigned long t)
|
||||||
{
|
{
|
||||||
uint32_t tstart;
|
uint32_t tstart;
|
||||||
static uint32_t last_1hz, last_50hz, last_5s;
|
static uint32_t last_1hz, last_50hz, last_5s;
|
||||||
|
@ -1963,7 +1963,7 @@ GCS_MAVLINK::queued_waypoint_send()
|
|||||||
MAVLink to process packets while waiting for the initialisation to
|
MAVLink to process packets while waiting for the initialisation to
|
||||||
complete
|
complete
|
||||||
*/
|
*/
|
||||||
static void mavlink_delay(uint32_t t)
|
static void mavlink_delay(unsigned long t)
|
||||||
{
|
{
|
||||||
uint32_t tstart;
|
uint32_t tstart;
|
||||||
static uint32_t last_1hz, last_50hz, last_5s;
|
static uint32_t last_1hz, last_50hz, last_5s;
|
||||||
|
Loading…
Reference in New Issue
Block a user