mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_HAL: removed the defer_timer_process() function
this is now unused
This commit is contained in:
parent
9548e7e79e
commit
93040e5725
@ -18,7 +18,6 @@ public:
|
|||||||
virtual void register_delay_callback(AP_HAL::Proc,
|
virtual void register_delay_callback(AP_HAL::Proc,
|
||||||
uint16_t min_time_ms) = 0;
|
uint16_t min_time_ms) = 0;
|
||||||
virtual void register_timer_process(AP_HAL::TimedProc) = 0;
|
virtual void register_timer_process(AP_HAL::TimedProc) = 0;
|
||||||
virtual bool defer_timer_process(AP_HAL::TimedProc) = 0;
|
|
||||||
virtual void register_timer_failsafe(AP_HAL::TimedProc,
|
virtual void register_timer_failsafe(AP_HAL::TimedProc,
|
||||||
uint32_t period_us) = 0;
|
uint32_t period_us) = 0;
|
||||||
virtual void suspend_timer_procs() = 0;
|
virtual void suspend_timer_procs() = 0;
|
||||||
|
@ -23,7 +23,6 @@ AVRTimer AVRScheduler::_timer;
|
|||||||
AP_HAL::TimedProc AVRScheduler::_failsafe = NULL;
|
AP_HAL::TimedProc AVRScheduler::_failsafe = NULL;
|
||||||
volatile bool AVRScheduler::_timer_suspended = false;
|
volatile bool AVRScheduler::_timer_suspended = false;
|
||||||
AP_HAL::TimedProc AVRScheduler::_timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
|
AP_HAL::TimedProc AVRScheduler::_timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
|
||||||
AP_HAL::TimedProc AVRScheduler::_defered_timer_proc = NULL;
|
|
||||||
uint8_t AVRScheduler::_num_timer_procs = 0;
|
uint8_t AVRScheduler::_num_timer_procs = 0;
|
||||||
bool AVRScheduler::_in_timer_proc = false;
|
bool AVRScheduler::_in_timer_proc = false;
|
||||||
|
|
||||||
@ -108,19 +107,6 @@ void AVRScheduler::register_timer_process(AP_HAL::TimedProc proc) {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AVRScheduler::defer_timer_process(AP_HAL::TimedProc proc) {
|
|
||||||
if ( _in_timer_proc || _timer_suspended ) {
|
|
||||||
_defered_timer_proc = proc;
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
_timer_suspended = true;
|
|
||||||
sei();
|
|
||||||
proc(_timer.micros());
|
|
||||||
_timer_suspended = false;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void AVRScheduler::register_timer_failsafe(
|
void AVRScheduler::register_timer_failsafe(
|
||||||
AP_HAL::TimedProc failsafe, uint32_t period_us) {
|
AP_HAL::TimedProc failsafe, uint32_t period_us) {
|
||||||
/* XXX Assert period_us == 1000 */
|
/* XXX Assert period_us == 1000 */
|
||||||
@ -174,18 +160,6 @@ void AVRScheduler::_timer_event() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Run any defered procedures, if they exist.*/
|
|
||||||
cli();
|
|
||||||
/* Atomic read and clear: */
|
|
||||||
AP_HAL::TimedProc defered = _defered_timer_proc;
|
|
||||||
_defered_timer_proc = NULL;
|
|
||||||
sei();
|
|
||||||
if (defered != NULL) {
|
|
||||||
_timer_suspended = true;
|
|
||||||
defered(tnow);
|
|
||||||
_timer_suspended = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// and the failsafe, if one is setup
|
// and the failsafe, if one is setup
|
||||||
if (_failsafe != NULL) {
|
if (_failsafe != NULL) {
|
||||||
_failsafe(tnow);
|
_failsafe(tnow);
|
||||||
|
@ -31,7 +31,6 @@ public:
|
|||||||
void delay_microseconds(uint16_t us);
|
void delay_microseconds(uint16_t us);
|
||||||
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
|
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
|
||||||
void register_timer_process(AP_HAL::TimedProc);
|
void register_timer_process(AP_HAL::TimedProc);
|
||||||
bool defer_timer_process(AP_HAL::TimedProc);
|
|
||||||
void register_timer_failsafe(AP_HAL::TimedProc, uint32_t period_us);
|
void register_timer_failsafe(AP_HAL::TimedProc, uint32_t period_us);
|
||||||
void suspend_timer_procs();
|
void suspend_timer_procs();
|
||||||
void resume_timer_procs();
|
void resume_timer_procs();
|
||||||
@ -54,7 +53,6 @@ private:
|
|||||||
|
|
||||||
static volatile bool _timer_suspended;
|
static volatile bool _timer_suspended;
|
||||||
static AP_HAL::TimedProc _timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS];
|
static AP_HAL::TimedProc _timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS];
|
||||||
static AP_HAL::TimedProc _defered_timer_proc;
|
|
||||||
static uint8_t _num_timer_procs;
|
static uint8_t _num_timer_procs;
|
||||||
static bool _in_timer_proc;
|
static bool _in_timer_proc;
|
||||||
|
|
||||||
|
@ -16,7 +16,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
AP_HAL::TimedProc SITLScheduler::_failsafe = NULL;
|
AP_HAL::TimedProc SITLScheduler::_failsafe = NULL;
|
||||||
volatile bool SITLScheduler::_timer_suspended = false;
|
volatile bool SITLScheduler::_timer_suspended = false;
|
||||||
AP_HAL::TimedProc SITLScheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
|
AP_HAL::TimedProc SITLScheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
|
||||||
AP_HAL::TimedProc SITLScheduler::_defered_timer_proc = NULL;
|
|
||||||
uint8_t SITLScheduler::_num_timer_procs = 0;
|
uint8_t SITLScheduler::_num_timer_procs = 0;
|
||||||
bool SITLScheduler::_in_timer_proc = false;
|
bool SITLScheduler::_in_timer_proc = false;
|
||||||
struct timeval SITLScheduler::_sketch_start_time;
|
struct timeval SITLScheduler::_sketch_start_time;
|
||||||
@ -100,19 +99,6 @@ void SITLScheduler::register_timer_process(AP_HAL::TimedProc proc)
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool SITLScheduler::defer_timer_process(AP_HAL::TimedProc proc)
|
|
||||||
{
|
|
||||||
if ( _in_timer_proc || _timer_suspended ) {
|
|
||||||
_defered_timer_proc = proc;
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
_timer_suspended = true;
|
|
||||||
proc(micros());
|
|
||||||
_timer_suspended = false;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void SITLScheduler::register_timer_failsafe(AP_HAL::TimedProc failsafe, uint32_t period_us)
|
void SITLScheduler::register_timer_failsafe(AP_HAL::TimedProc failsafe, uint32_t period_us)
|
||||||
{
|
{
|
||||||
_failsafe = failsafe;
|
_failsafe = failsafe;
|
||||||
@ -173,16 +159,6 @@ void SITLScheduler::timer_event()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Run any defered procedures, if they exist.*/
|
|
||||||
/* Atomic read and clear: */
|
|
||||||
AP_HAL::TimedProc defered = _defered_timer_proc;
|
|
||||||
_defered_timer_proc = NULL;
|
|
||||||
if (defered != NULL) {
|
|
||||||
_timer_suspended = true;
|
|
||||||
defered(tnow);
|
|
||||||
_timer_suspended = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// and the failsafe, if one is setup
|
// and the failsafe, if one is setup
|
||||||
if (_failsafe != NULL) {
|
if (_failsafe != NULL) {
|
||||||
_failsafe(tnow);
|
_failsafe(tnow);
|
||||||
|
@ -22,7 +22,6 @@ public:
|
|||||||
void delay_microseconds(uint16_t us);
|
void delay_microseconds(uint16_t us);
|
||||||
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
|
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
|
||||||
void register_timer_process(AP_HAL::TimedProc);
|
void register_timer_process(AP_HAL::TimedProc);
|
||||||
bool defer_timer_process(AP_HAL::TimedProc);
|
|
||||||
void register_timer_failsafe(AP_HAL::TimedProc, uint32_t period_us);
|
void register_timer_failsafe(AP_HAL::TimedProc, uint32_t period_us);
|
||||||
void suspend_timer_procs();
|
void suspend_timer_procs();
|
||||||
void resume_timer_procs();
|
void resume_timer_procs();
|
||||||
@ -47,7 +46,6 @@ private:
|
|||||||
|
|
||||||
static volatile bool _timer_suspended;
|
static volatile bool _timer_suspended;
|
||||||
static AP_HAL::TimedProc _timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS];
|
static AP_HAL::TimedProc _timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS];
|
||||||
static AP_HAL::TimedProc _defered_timer_proc;
|
|
||||||
static uint8_t _num_timer_procs;
|
static uint8_t _num_timer_procs;
|
||||||
static bool _in_timer_proc;
|
static bool _in_timer_proc;
|
||||||
|
|
||||||
|
@ -32,11 +32,6 @@ void EmptyScheduler::register_delay_callback(AP_HAL::Proc k,
|
|||||||
void EmptyScheduler::register_timer_process(AP_HAL::TimedProc k)
|
void EmptyScheduler::register_timer_process(AP_HAL::TimedProc k)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
bool EmptyScheduler::defer_timer_process(AP_HAL::TimedProc k) {
|
|
||||||
if (k) k(5000);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void EmptyScheduler::register_timer_failsafe(AP_HAL::TimedProc,
|
void EmptyScheduler::register_timer_failsafe(AP_HAL::TimedProc,
|
||||||
uint32_t period_us)
|
uint32_t period_us)
|
||||||
{}
|
{}
|
||||||
|
@ -15,7 +15,6 @@ public:
|
|||||||
void register_delay_callback(AP_HAL::Proc,
|
void register_delay_callback(AP_HAL::Proc,
|
||||||
uint16_t min_time_ms);
|
uint16_t min_time_ms);
|
||||||
void register_timer_process(AP_HAL::TimedProc);
|
void register_timer_process(AP_HAL::TimedProc);
|
||||||
bool defer_timer_process(AP_HAL::TimedProc);
|
|
||||||
void register_timer_failsafe(AP_HAL::TimedProc,
|
void register_timer_failsafe(AP_HAL::TimedProc,
|
||||||
uint32_t period_us);
|
uint32_t period_us);
|
||||||
void suspend_timer_procs();
|
void suspend_timer_procs();
|
||||||
|
Loading…
Reference in New Issue
Block a user