mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
HAL_ChibiOS: added IRQ save/restore to hal.scheduler
these are used by RPM driver
This commit is contained in:
parent
d2075b4b67
commit
51c40a013b
@ -416,4 +416,22 @@ void Scheduler::system_initialized()
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
/*
|
||||
disable interrupts and return a context that can be used to
|
||||
restore the interrupt state. This can be used to protect
|
||||
critical regions
|
||||
*/
|
||||
void *Scheduler::disable_interrupts_save(void)
|
||||
{
|
||||
return (void *)(uintptr_t)chSysGetStatusAndLockX();
|
||||
}
|
||||
|
||||
/*
|
||||
restore interrupt state from disable_interrupts_save()
|
||||
*/
|
||||
void Scheduler::restore_interrupts(void *state)
|
||||
{
|
||||
chSysRestoreStatusX((syssts_t)(uintptr_t)state);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -75,6 +75,18 @@ public:
|
||||
void hal_initialized() { _hal_initialized = true; }
|
||||
|
||||
bool check_called_boost(void);
|
||||
|
||||
/*
|
||||
disable interrupts and return a context that can be used to
|
||||
restore the interrupt state. This can be used to protect
|
||||
critical regions
|
||||
*/
|
||||
void *disable_interrupts_save(void) override;
|
||||
|
||||
/*
|
||||
restore interrupt state from disable_interrupts_save()
|
||||
*/
|
||||
void restore_interrupts(void *) override;
|
||||
|
||||
private:
|
||||
bool _initialized;
|
||||
|
Loading…
Reference in New Issue
Block a user