2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-01-02 06:39:26 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
#include "AP_HAL_PX4_Namespace.h"
|
|
|
|
#include <sys/time.h>
|
|
|
|
#include <signal.h>
|
2013-01-20 22:54:09 -04:00
|
|
|
#include <pthread.h>
|
2013-01-24 00:02:50 -04:00
|
|
|
#include <systemlib/perf_counter.h>
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2013-01-20 22:54:09 -04:00
|
|
|
#define PX4_SCHEDULER_MAX_TIMER_PROCS 8
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2018-08-01 05:56:50 -03:00
|
|
|
#define APM_MAX_PRIORITY 243
|
2015-02-15 20:53:08 -04:00
|
|
|
#define APM_MAIN_PRIORITY_BOOST 241
|
|
|
|
#define APM_MAIN_PRIORITY 180
|
|
|
|
#define APM_TIMER_PRIORITY 181
|
2016-11-02 06:26:52 -03:00
|
|
|
#define APM_SPI_PRIORITY 242
|
2017-04-02 11:55:00 -03:00
|
|
|
#define APM_CAN_PRIORITY 179
|
2016-10-31 04:57:44 -03:00
|
|
|
#define APM_I2C_PRIORITY 178
|
2015-02-15 20:53:08 -04:00
|
|
|
#define APM_UART_PRIORITY 60
|
2015-03-04 05:07:11 -04:00
|
|
|
#define APM_STORAGE_PRIORITY 59
|
|
|
|
#define APM_IO_PRIORITY 58
|
2015-06-17 04:04:51 -03:00
|
|
|
#define APM_SHELL_PRIORITY 57
|
2015-02-15 20:53:08 -04:00
|
|
|
#define APM_OVERTIME_PRIORITY 10
|
|
|
|
#define APM_STARTUP_PRIORITY 10
|
|
|
|
|
|
|
|
/* how long to boost priority of the main thread for each main
|
|
|
|
loop. This needs to be long enough for all interrupt-level drivers
|
|
|
|
(mostly SPI drivers) to run, and for the main loop of the vehicle
|
|
|
|
code to start the AHRS update.
|
|
|
|
|
|
|
|
Priority boosting of the main thread in delay_microseconds_boost()
|
|
|
|
avoids the problem that drivers in hpwork all happen to run right
|
|
|
|
at the start of the period where the main vehicle loop is calling
|
|
|
|
wait_for_sample(). That causes main loop timing jitter, which
|
|
|
|
reduces performance. Using the priority boost the main loop
|
|
|
|
temporarily runs at a priority higher than hpwork and the timer
|
|
|
|
thread, which results in much more consistent loop timing.
|
|
|
|
*/
|
|
|
|
#define APM_MAIN_PRIORITY_BOOST_USEC 150
|
2013-01-24 00:02:50 -04:00
|
|
|
|
2015-02-06 17:06:53 -04:00
|
|
|
#define APM_MAIN_THREAD_STACK_SIZE 8192
|
|
|
|
|
2013-01-02 06:39:26 -04:00
|
|
|
/* Scheduler implementation: */
|
|
|
|
class PX4::PX4Scheduler : public AP_HAL::Scheduler {
|
|
|
|
public:
|
|
|
|
PX4Scheduler();
|
|
|
|
/* AP_HAL::Scheduler methods */
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void init();
|
2013-01-02 06:39:26 -04:00
|
|
|
void delay(uint16_t ms);
|
|
|
|
void delay_microseconds(uint16_t us);
|
2015-02-15 20:53:08 -04:00
|
|
|
void delay_microseconds_boost(uint16_t us);
|
2013-09-30 07:36:19 -03:00
|
|
|
void register_timer_process(AP_HAL::MemberProc);
|
|
|
|
void register_io_process(AP_HAL::MemberProc);
|
|
|
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
2013-09-03 22:58:13 -03:00
|
|
|
void reboot(bool hold_in_bootloader);
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2017-09-17 22:03:05 -03:00
|
|
|
bool in_main_thread() const override;
|
2013-01-10 21:20:43 -04:00
|
|
|
void system_initialized();
|
2013-10-28 02:10:51 -03:00
|
|
|
void hal_initialized() { _hal_initialized = true; }
|
2017-04-02 11:55:00 -03:00
|
|
|
|
|
|
|
void create_uavcan_thread() override;
|
|
|
|
|
2018-03-28 05:49:51 -03:00
|
|
|
/*
|
|
|
|
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;
|
2018-08-01 05:56:50 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
create a new thread
|
|
|
|
*/
|
|
|
|
bool thread_create(AP_HAL::MemberProc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) override;
|
2018-03-28 05:49:51 -03:00
|
|
|
|
2013-01-02 06:39:26 -04:00
|
|
|
private:
|
2013-01-10 21:20:43 -04:00
|
|
|
bool _initialized;
|
2013-10-28 02:10:51 -03:00
|
|
|
volatile bool _hal_initialized;
|
2013-01-02 06:39:26 -04:00
|
|
|
AP_HAL::Proc _delay_cb;
|
|
|
|
uint16_t _min_delay_cb_ms;
|
2013-09-30 07:36:19 -03:00
|
|
|
AP_HAL::Proc _failsafe;
|
2013-01-20 22:54:09 -04:00
|
|
|
|
2013-09-30 07:36:19 -03:00
|
|
|
AP_HAL::MemberProc _timer_proc[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
2013-01-20 22:54:09 -04:00
|
|
|
uint8_t _num_timer_procs;
|
|
|
|
volatile bool _in_timer_proc;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
2013-09-30 07:36:19 -03:00
|
|
|
AP_HAL::MemberProc _io_proc[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
2013-04-17 08:33:50 -03:00
|
|
|
uint8_t _num_io_procs;
|
|
|
|
volatile bool _in_io_proc;
|
|
|
|
|
2013-10-19 02:47:35 -03:00
|
|
|
pid_t _main_task_pid;
|
2013-01-24 00:02:50 -04:00
|
|
|
pthread_t _timer_thread_ctx;
|
|
|
|
pthread_t _io_thread_ctx;
|
2015-03-04 05:07:11 -04:00
|
|
|
pthread_t _storage_thread_ctx;
|
2013-09-04 00:15:27 -03:00
|
|
|
pthread_t _uart_thread_ctx;
|
2017-04-02 11:55:00 -03:00
|
|
|
pthread_t _uavcan_thread_ctx;
|
2013-01-24 00:02:50 -04:00
|
|
|
|
2017-05-06 06:12:35 -03:00
|
|
|
struct _uavcan_thread_arg {
|
|
|
|
PX4Scheduler *sched;
|
|
|
|
uint8_t uavcan_number;
|
|
|
|
};
|
|
|
|
|
AP_HAL_PX4: fix passing callback to member function
This is the same approach as done for AP_HAL_Linux in e3d78b8 ("AP_HAL_Linux:
fix passing callback to member function"). It fixes the following warnings:
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp: In member function 'virtual void PX4::PX4Scheduler::init(void*)':
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:55:95: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_timer_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_timer_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:65:94: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_uart_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_uart_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:75:92: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
^
ardupilot/libraries/AP_HAL_PX4/Scheduler.cpp:85:100: warning: converting from 'void* (PX4::PX4Scheduler::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&_storage_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_storage_thread, this);
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp: In member function 'void PX4::NSHShellStream::start_shell()':
ardupilot/libraries/AP_HAL_PX4/NSHShellStream.cpp:83:99: warning: converting from 'void (PX4::NSHShellStream::*)()' to 'pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
pthread_create(&shell_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::NSHShellStream::shell_thread, this);
^
2015-11-25 13:30:34 -04:00
|
|
|
static void *_timer_thread(void *arg);
|
|
|
|
static void *_io_thread(void *arg);
|
|
|
|
static void *_storage_thread(void *arg);
|
|
|
|
static void *_uart_thread(void *arg);
|
2017-04-02 11:55:00 -03:00
|
|
|
static void *_uavcan_thread(void *arg);
|
2013-01-24 00:02:50 -04:00
|
|
|
|
2018-05-13 19:47:25 -03:00
|
|
|
void _run_timers();
|
2013-04-17 08:33:50 -03:00
|
|
|
void _run_io(void);
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2013-10-13 18:29:30 -03:00
|
|
|
void delay_microseconds_semaphore(uint16_t us);
|
|
|
|
|
2013-01-24 00:02:50 -04:00
|
|
|
perf_counter_t _perf_timers;
|
2013-04-17 08:33:50 -03:00
|
|
|
perf_counter_t _perf_io_timers;
|
2015-03-04 05:07:11 -04:00
|
|
|
perf_counter_t _perf_storage_timer;
|
2013-01-24 00:02:50 -04:00
|
|
|
perf_counter_t _perf_delay;
|
2018-08-01 05:56:50 -03:00
|
|
|
static void *thread_create_trampoline(void *ctx);
|
2013-01-02 06:39:26 -04:00
|
|
|
};
|
|
|
|
#endif
|