Browse Source

AP_HAL_PX4: added IRQ save/restore to hal.scheduler

these are used by RPM driver
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
9942934f0d
  1. 19
      libraries/AP_HAL_PX4/Scheduler.cpp
  2. 12
      libraries/AP_HAL_PX4/Scheduler.h

19
libraries/AP_HAL_PX4/Scheduler.cpp

@ -457,4 +457,23 @@ void PX4Scheduler::system_initialized() @@ -457,4 +457,23 @@ void PX4Scheduler::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 *PX4Scheduler::disable_interrupts_save(void)
{
return (void *)(uintptr_t)irqsave();
}
/*
restore interrupt state from disable_interrupts_save()
*/
void PX4Scheduler::restore_interrupts(void *state)
{
irqrestore((irqstate_t)(uintptr_t)state);
}
#endif

12
libraries/AP_HAL_PX4/Scheduler.h

@ -64,6 +64,18 @@ public: @@ -64,6 +64,18 @@ public:
void create_uavcan_thread() override;
/*
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;
volatile bool _hal_initialized;

Loading…
Cancel
Save