mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scheduler:time_available value type invalid uint16_t to valid uint32_t.
This commit is contained in:
parent
d8b58690ad
commit
7721290160
@ -89,7 +89,7 @@ void AP_Scheduler::tick(void)
|
|||||||
run one tick
|
run one tick
|
||||||
this will run as many scheduler tasks as we can in the specified time
|
this will run as many scheduler tasks as we can in the specified time
|
||||||
*/
|
*/
|
||||||
void AP_Scheduler::run(uint16_t time_available)
|
void AP_Scheduler::run(uint32_t time_available)
|
||||||
{
|
{
|
||||||
uint32_t run_started_usec = AP_HAL::micros();
|
uint32_t run_started_usec = AP_HAL::micros();
|
||||||
uint32_t now = run_started_usec;
|
uint32_t now = run_started_usec;
|
||||||
|
@ -73,7 +73,7 @@ public:
|
|||||||
// run the tasks. Call this once per 'tick'.
|
// run the tasks. Call this once per 'tick'.
|
||||||
// time_available is the amount of time available to run
|
// time_available is the amount of time available to run
|
||||||
// tasks in microseconds
|
// tasks in microseconds
|
||||||
void run(uint16_t time_available);
|
void run(uint32_t time_available);
|
||||||
|
|
||||||
// return the number of microseconds available for the current task
|
// return the number of microseconds available for the current task
|
||||||
uint16_t time_available_usec(void);
|
uint16_t time_available_usec(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user