mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_HAL_SITL: Scheduler remove unreachable code & minor fix
usleep wasn't reached since synthetic clock is always used correct style make constructor explicit use c++ cast
This commit is contained in:
parent
63b3618fc7
commit
ab9e88299f
@ -5,7 +5,6 @@
|
|||||||
#include "Scheduler.h"
|
#include "Scheduler.h"
|
||||||
#include "UARTDriver.h"
|
#include "UARTDriver.h"
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include <unistd.h>
|
|
||||||
#include <fenv.h>
|
#include <fenv.h>
|
||||||
|
|
||||||
using namespace HALSITL;
|
using namespace HALSITL;
|
||||||
@ -43,11 +42,7 @@ void Scheduler::delay_microseconds(uint16_t usec)
|
|||||||
if (dtime >= usec) {
|
if (dtime >= usec) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (_stopped_clock_usec) {
|
|
||||||
_sitlState->wait_clock(start + usec);
|
_sitlState->wait_clock(start + usec);
|
||||||
} else {
|
|
||||||
usleep(usec - dtime);
|
|
||||||
}
|
|
||||||
} while (true);
|
} while (true);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -83,7 +78,6 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
|||||||
_timer_proc[_num_timer_procs] = proc;
|
_timer_proc[_num_timer_procs] = proc;
|
||||||
_num_timer_procs++;
|
_num_timer_procs++;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
||||||
@ -98,7 +92,6 @@ void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
|||||||
_io_proc[_num_io_procs] = proc;
|
_io_proc[_num_io_procs] = proc;
|
||||||
_num_io_procs++;
|
_num_io_procs++;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
||||||
@ -141,11 +134,12 @@ void Scheduler::system_initialized() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void Scheduler::sitl_end_atomic() {
|
void Scheduler::sitl_end_atomic() {
|
||||||
if (_nested_atomic_ctr == 0)
|
if (_nested_atomic_ctr == 0) {
|
||||||
hal.uartA->println("NESTED ATOMIC ERROR");
|
hal.uartA->println("NESTED ATOMIC ERROR");
|
||||||
else
|
} else {
|
||||||
_nested_atomic_ctr--;
|
_nested_atomic_ctr--;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void Scheduler::reboot(bool hold_in_bootloader)
|
void Scheduler::reboot(bool hold_in_bootloader)
|
||||||
{
|
{
|
||||||
|
@ -10,7 +10,7 @@
|
|||||||
/* Scheduler implementation: */
|
/* Scheduler implementation: */
|
||||||
class HALSITL::Scheduler : public AP_HAL::Scheduler {
|
class HALSITL::Scheduler : public AP_HAL::Scheduler {
|
||||||
public:
|
public:
|
||||||
Scheduler(SITL_State *sitlState);
|
explicit Scheduler(SITL_State *sitlState);
|
||||||
static Scheduler *from(AP_HAL::Scheduler *scheduler) {
|
static Scheduler *from(AP_HAL::Scheduler *scheduler) {
|
||||||
return static_cast<HALSITL::Scheduler*>(scheduler);
|
return static_cast<HALSITL::Scheduler*>(scheduler);
|
||||||
}
|
}
|
||||||
@ -76,7 +76,3 @@ private:
|
|||||||
uint64_t _stopped_clock_usec;
|
uint64_t _stopped_clock_usec;
|
||||||
};
|
};
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user