mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
AP_HAL_Linux: Remove timer process suspension interface
This commit is contained in:
parent
0f2482f05b
commit
80d1a1de9a
@ -64,9 +64,7 @@ void AnalogIn_ADS1115::init()
|
|||||||
{
|
{
|
||||||
_adc->init();
|
_adc->init();
|
||||||
|
|
||||||
hal.scheduler->suspend_timer_procs();
|
|
||||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AnalogIn_ADS1115::_update, void));
|
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AnalogIn_ADS1115::_update, void));
|
||||||
hal.scheduler->resume_timer_procs();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AnalogIn_ADS1115::_update()
|
void AnalogIn_ADS1115::_update()
|
||||||
|
@ -23,6 +23,7 @@ AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float volta
|
|||||||
_sum_count(0),
|
_sum_count(0),
|
||||||
_pin_fd(-1)
|
_pin_fd(-1)
|
||||||
{
|
{
|
||||||
|
_semaphore = hal.util->new_semaphore();
|
||||||
init_pins();
|
init_pins();
|
||||||
select_pin();
|
select_pin();
|
||||||
}
|
}
|
||||||
@ -50,14 +51,16 @@ void AnalogSource_IIO::select_pin(void)
|
|||||||
float AnalogSource_IIO::read_average()
|
float AnalogSource_IIO::read_average()
|
||||||
{
|
{
|
||||||
read_latest();
|
read_latest();
|
||||||
if (_sum_count == 0) {
|
if (_semaphore->take(1)) {
|
||||||
return _value;
|
if (_sum_count == 0) {
|
||||||
|
_semaphore->give();
|
||||||
|
return _value;
|
||||||
|
}
|
||||||
|
_value = _sum_value / _sum_count;
|
||||||
|
_sum_value = 0;
|
||||||
|
_sum_count = 0;
|
||||||
|
_semaphore->give();
|
||||||
}
|
}
|
||||||
hal.scheduler->suspend_timer_procs();
|
|
||||||
_value = _sum_value / _sum_count;
|
|
||||||
_sum_value = 0;
|
|
||||||
_sum_count = 0;
|
|
||||||
hal.scheduler->resume_timer_procs();
|
|
||||||
return _value;
|
return _value;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -75,9 +78,12 @@ float AnalogSource_IIO::read_latest()
|
|||||||
_latest = 0;
|
_latest = 0;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
_latest = atoi(sbuf) * _voltage_scaling;
|
if (_semaphore->take(1)) {
|
||||||
_sum_value += _latest;
|
_latest = atoi(sbuf) * _voltage_scaling;
|
||||||
_sum_count++;
|
_sum_value += _latest;
|
||||||
|
_sum_count++;
|
||||||
|
_semaphore->give();
|
||||||
|
}
|
||||||
|
|
||||||
return _latest;
|
return _latest;
|
||||||
}
|
}
|
||||||
@ -100,14 +106,15 @@ void AnalogSource_IIO::set_pin(uint8_t pin)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
hal.scheduler->suspend_timer_procs();
|
if (_semaphore->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||||
_pin = pin;
|
_pin = pin;
|
||||||
_sum_value = 0;
|
_sum_value = 0;
|
||||||
_sum_count = 0;
|
_sum_count = 0;
|
||||||
_latest = 0;
|
_latest = 0;
|
||||||
_value = 0;
|
_value = 0;
|
||||||
select_pin();
|
select_pin();
|
||||||
hal.scheduler->resume_timer_procs();
|
_semaphore->give();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AnalogSource_IIO::set_stop_pin(uint8_t p)
|
void AnalogSource_IIO::set_stop_pin(uint8_t p)
|
||||||
|
@ -45,6 +45,7 @@ private:
|
|||||||
int16_t _pin;
|
int16_t _pin;
|
||||||
int _pin_fd;
|
int _pin_fd;
|
||||||
int fd_analog_sources[IIO_ANALOG_IN_COUNT];
|
int fd_analog_sources[IIO_ANALOG_IN_COUNT];
|
||||||
|
AP_HAL::Semaphore *_semaphore;
|
||||||
|
|
||||||
void init_pins(void);
|
void init_pins(void);
|
||||||
void select_pin(void);
|
void select_pin(void);
|
||||||
|
@ -208,18 +208,6 @@ void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_u
|
|||||||
_failsafe = failsafe;
|
_failsafe = failsafe;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Scheduler::suspend_timer_procs()
|
|
||||||
{
|
|
||||||
if (!_timer_semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
|
||||||
printf("Failed to take timer semaphore\n");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void Scheduler::resume_timer_procs()
|
|
||||||
{
|
|
||||||
_timer_semaphore.give();
|
|
||||||
}
|
|
||||||
|
|
||||||
void Scheduler::_timer_task()
|
void Scheduler::_timer_task()
|
||||||
{
|
{
|
||||||
int i;
|
int i;
|
||||||
@ -229,11 +217,6 @@ void Scheduler::_timer_task()
|
|||||||
}
|
}
|
||||||
_in_timer_proc = true;
|
_in_timer_proc = true;
|
||||||
|
|
||||||
if (!_timer_semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
|
||||||
printf("Failed to take timer semaphore in %s\n", __PRETTY_FUNCTION__);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// now call the timer based drivers
|
// now call the timer based drivers
|
||||||
for (i = 0; i < _num_timer_procs; i++) {
|
for (i = 0; i < _num_timer_procs; i++) {
|
||||||
if (_timer_proc[i]) {
|
if (_timer_proc[i]) {
|
||||||
@ -241,8 +224,6 @@ void Scheduler::_timer_task()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
_timer_semaphore.give();
|
|
||||||
|
|
||||||
// and the failsafe, if one is setup
|
// and the failsafe, if one is setup
|
||||||
if (_failsafe != nullptr) {
|
if (_failsafe != nullptr) {
|
||||||
_failsafe();
|
_failsafe();
|
||||||
|
@ -30,8 +30,6 @@ public:
|
|||||||
|
|
||||||
void register_timer_process(AP_HAL::MemberProc);
|
void register_timer_process(AP_HAL::MemberProc);
|
||||||
void register_io_process(AP_HAL::MemberProc);
|
void register_io_process(AP_HAL::MemberProc);
|
||||||
void suspend_timer_procs();
|
|
||||||
void resume_timer_procs();
|
|
||||||
|
|
||||||
bool in_main_thread() const override;
|
bool in_main_thread() const override;
|
||||||
|
|
||||||
@ -98,7 +96,6 @@ private:
|
|||||||
uint64_t _last_stack_debug_msec;
|
uint64_t _last_stack_debug_msec;
|
||||||
pthread_t _main_ctx;
|
pthread_t _main_ctx;
|
||||||
|
|
||||||
Semaphore _timer_semaphore;
|
|
||||||
Semaphore _io_semaphore;
|
Semaphore _io_semaphore;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user