mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_Linux: split out a calculate_thread_priority method
This commit is contained in:
parent
cfacb5d34d
commit
d0b3b926c0
@ -348,16 +348,9 @@ void Scheduler::teardown()
|
||||
_uart_thread.join();
|
||||
}
|
||||
|
||||
/*
|
||||
create a new thread
|
||||
*/
|
||||
bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority)
|
||||
// calculates an integer to be used as the priority for a newly-created thread
|
||||
uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority) const
|
||||
{
|
||||
Thread *thread = new Thread{(Thread::task_t)proc};
|
||||
if (!thread) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t thread_priority = APM_LINUX_IO_PRIORITY;
|
||||
static const struct {
|
||||
priority_base base;
|
||||
@ -382,6 +375,21 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
||||
}
|
||||
}
|
||||
|
||||
return thread_priority;
|
||||
}
|
||||
|
||||
/*
|
||||
create a new thread
|
||||
*/
|
||||
bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority)
|
||||
{
|
||||
Thread *thread = new Thread{(Thread::task_t)proc};
|
||||
if (!thread) {
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint8_t thread_priority = calculate_thread_priority(base, priority);
|
||||
|
||||
// Add 256k to HAL-independent requested stack size
|
||||
thread->set_stack_size(256 * 1024 + stack_size);
|
||||
|
||||
|
@ -86,6 +86,10 @@ private:
|
||||
AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS];
|
||||
uint8_t _num_io_procs;
|
||||
|
||||
// calculates an integer to be used as the priority for a
|
||||
// newly-created thread
|
||||
uint8_t calculate_thread_priority(priority_base base, int8_t priority) const;
|
||||
|
||||
SchedulerThread _timer_thread{FUNCTOR_BIND_MEMBER(&Scheduler::_timer_task, void), *this};
|
||||
SchedulerThread _io_thread{FUNCTOR_BIND_MEMBER(&Scheduler::_io_task, void), *this};
|
||||
SchedulerThread _rcin_thread{FUNCTOR_BIND_MEMBER(&Scheduler::_rcin_task, void), *this};
|
||||
|
Loading…
Reference in New Issue
Block a user