2 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 12 #include <drivers/drv_hrt.h> 13 #include <nuttx/arch.h> 14 #include <systemlib/systemlib.h> 39 _perf_timers(perf_alloc(PC_ELAPSED,
"APM_timers")),
40 _perf_io_timers(perf_alloc(PC_ELAPSED,
"APM_IO_timers")),
41 _perf_storage_timer(perf_alloc(PC_ELAPSED,
"APM_storage_timers")),
42 _perf_delay(perf_alloc(PC_ELAPSED,
"APM_delay"))
50 pthread_attr_t thread_attr;
51 struct sched_param param;
53 pthread_attr_init(&thread_attr);
54 pthread_attr_setstacksize(&thread_attr, 2048);
57 (void)pthread_attr_setschedparam(&thread_attr, ¶m);
58 pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
63 pthread_attr_init(&thread_attr);
64 pthread_attr_setstacksize(&thread_attr, 2048);
67 (void)pthread_attr_setschedparam(&thread_attr, ¶m);
68 pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
73 pthread_attr_init(&thread_attr);
74 pthread_attr_setstacksize(&thread_attr, 2048);
77 (void)pthread_attr_setschedparam(&thread_attr, ¶m);
78 pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
83 pthread_attr_init(&thread_attr);
84 pthread_attr_setstacksize(&thread_attr, 1024);
87 (void)pthread_attr_setschedparam(&thread_attr, ¶m);
88 pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
96 pthread_attr_t thread_attr;
97 struct sched_param param;
100 pthread_attr_init(&thread_attr);
101 pthread_attr_setstacksize(&thread_attr, 8192);
104 (void) pthread_attr_setschedparam(&thread_attr, ¶m);
105 pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
107 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
108 if (hal.
can_mgr[i] !=
nullptr) {
109 if (hal.
can_mgr[i]->get_UAVCAN() !=
nullptr) {
126 sem_t wait_semaphore;
127 struct hrt_call wait_call;
128 sem_init(&wait_semaphore, 0, 0);
129 memset(&wait_call, 0,
sizeof(wait_call));
130 hrt_call_after(&wait_call, usec, (hrt_callout)sem_post, &wait_semaphore);
131 sem_wait(&wait_semaphore);
166 sem_t wait_semaphore;
167 static struct hrt_call wait_call;
168 sem_init(&wait_semaphore, 0, 0);
169 hrt_call_after(&wait_call, usec, (hrt_callout)
sem_post_boost, &wait_semaphore);
170 sem_wait(&wait_semaphore);
177 ::printf(
"ERROR: delay() from timer process\n");
256 px4_systemreset(hold_in_bootloader);
273 }
else if (called_from_timer_thread) {
293 uint32_t last_ran_overtime = 0;
295 pthread_setname_np(pthread_self(),
"apm_timer");
318 hal.
console->
printf(
"Overtime in task %d\n", (
int)AP_Scheduler::current_task);
348 pthread_setname_np(pthread_self(),
"apm_uart");
371 pthread_setname_np(pthread_self(),
"apm_io");
391 pthread_setname_np(pthread_self(),
"apm_storage");
414 snprintf(name,
sizeof(name),
"apm_uavcan:%u", uavcan_number);
415 pthread_setname_np(pthread_self(), name);
459 return (
void *)(uintptr_t)irqsave();
467 irqrestore((irqstate_t)(uintptr_t)state);
int printf(const char *fmt,...)
bool in_main_thread() const override
static void set_normal_priority(void *sem)
virtual void force_safety_no_wait(void)
AP_HAL::UARTDriver * uartE
volatile bool _timer_suspended
pthread_t _uart_thread_ctx
#define APM_UART_PRIORITY
AP_HAL::UARTDriver * console
#define PX4_SCHEDULER_MAX_TIMER_PROCS
pthread_t _timer_thread_ctx
#define APM_MAIN_PRIORITY_BOOST
static int8_t current_task
#define APM_MAIN_PRIORITY
perf_counter_t _perf_delay
uint16_t _min_delay_cb_ms
AP_HAL::UARTDriver * uartB
perf_counter_t _perf_timers
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
static void * _uavcan_thread(void *arg)
void delay_microseconds(uint16_t us)
volatile bool _hal_initialized
AP_HAL::CANManager ** can_mgr
virtual void _timer_tick(void)
void create_uavcan_thread() override
AP_HAL::UARTDriver * uartC
virtual void _timer_tick(void)
virtual void printf(const char *,...) FMT_PRINTF(2
static void * _uart_thread(void *arg)
void * disable_interrupts_save(void) override
virtual void timer_tick(void)
void _run_timers(bool called_from_timer_thread)
AP_HAL::UARTDriver * uartF
AP_HAL::UARTDriver * uartD
AP_HAL::Storage * storage
pthread_t _uavcan_thread_ctx
void reboot(bool hold_in_bootloader)
virtual void call_delay_cb()
#define APM_MAIN_PRIORITY_BOOST_USEC
pthread_t _storage_thread_ctx
virtual bool force_safety_on(void)
static void * _timer_thread(void *arg)
volatile bool _in_timer_proc
void suspend_timer_procs()
perf_counter_t _perf_storage_timer
static void * _storage_thread(void *arg)
void hal_px4_set_priority(uint8_t priority)
static void * _io_thread(void *arg)
AP_HAL::UARTDriver * uartA
perf_counter_t _perf_io_timers
void system_initialized()
void register_timer_process(AP_HAL::MemberProc)
int snprintf(char *str, size_t size, const char *fmt,...)
volatile bool _timer_event_missed
void resume_timer_procs()
#define APM_STORAGE_PRIORITY
AP_HAL::MemberProc _timer_proc[PX4_SCHEDULER_MAX_TIMER_PROCS]
static void sem_post_boost(sem_t *sem)
void register_io_process(AP_HAL::MemberProc)
void delay_microseconds_semaphore(uint16_t us)
bool _px4_thread_should_exit
void panic(const char *errormsg,...) FMT_PRINTF(1
#define APM_TIMER_PRIORITY
void delay_microseconds_boost(uint16_t us)
void restore_interrupts(void *) override
volatile bool _in_io_proc
static const AP_HAL::HAL & hal
AP_HAL::MemberProc _io_proc[PX4_SCHEDULER_MAX_TIMER_PROCS]
AP_HAL::AnalogIn * analogin