2013-01-02 06:39:26 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
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.h"
|
|
|
|
#include "Scheduler.h"
|
2013-01-03 04:34:36 -04:00
|
|
|
|
2013-01-02 06:39:26 -04:00
|
|
|
#include <unistd.h>
|
2013-01-03 04:34:36 -04:00
|
|
|
#include <stdlib.h>
|
2013-01-02 06:39:26 -04:00
|
|
|
#include <sched.h>
|
|
|
|
#include <errno.h>
|
|
|
|
#include <stdio.h>
|
2013-01-02 22:15:57 -04:00
|
|
|
#include <drivers/drv_hrt.h>
|
|
|
|
#include <nuttx/arch.h>
|
2013-01-03 04:34:36 -04:00
|
|
|
#include <systemlib/systemlib.h>
|
2013-10-13 18:29:30 -03:00
|
|
|
#include <pthread.h>
|
2013-01-03 20:49:32 -04:00
|
|
|
#include <poll.h>
|
2013-01-24 00:02:50 -04:00
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
#include "UARTDriver.h"
|
2013-09-12 00:26:00 -03:00
|
|
|
#include "AnalogIn.h"
|
2013-01-23 01:37:11 -04:00
|
|
|
#include "Storage.h"
|
2013-01-25 04:16:28 -04:00
|
|
|
#include "RCOutput.h"
|
2013-01-26 21:51:34 -04:00
|
|
|
#include "RCInput.h"
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
2013-01-02 06:39:26 -04:00
|
|
|
|
|
|
|
using namespace PX4;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2013-01-20 22:54:09 -04:00
|
|
|
extern bool _px4_thread_should_exit;
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2013-01-24 00:02:50 -04:00
|
|
|
PX4Scheduler::PX4Scheduler() :
|
|
|
|
_perf_timers(perf_alloc(PC_ELAPSED, "APM_timers")),
|
2013-04-17 08:33:50 -03:00
|
|
|
_perf_io_timers(perf_alloc(PC_ELAPSED, "APM_IO_timers")),
|
2015-03-04 05:07:11 -04:00
|
|
|
_perf_storage_timer(perf_alloc(PC_ELAPSED, "APM_storage_timers")),
|
2013-01-24 00:02:50 -04:00
|
|
|
_perf_delay(perf_alloc(PC_ELAPSED, "APM_delay"))
|
2013-01-02 06:39:26 -04:00
|
|
|
{}
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void PX4Scheduler::init()
|
2013-01-02 06:39:26 -04:00
|
|
|
{
|
2013-10-19 02:47:35 -03:00
|
|
|
_main_task_pid = getpid();
|
|
|
|
|
2013-01-20 22:54:09 -04:00
|
|
|
// setup the timer thread - this will call tasks at 1kHz
|
|
|
|
pthread_attr_t thread_attr;
|
2013-01-24 00:02:50 -04:00
|
|
|
struct sched_param param;
|
|
|
|
|
2013-01-20 22:54:09 -04:00
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 2048);
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2013-01-24 00:02:50 -04:00
|
|
|
param.sched_priority = APM_TIMER_PRIORITY;
|
2013-01-20 22:54:09 -04:00
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
2013-01-24 00:02:50 -04:00
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
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
|
|
|
pthread_create(&_timer_thread_ctx, &thread_attr, &PX4Scheduler::_timer_thread, this);
|
2013-01-24 00:02:50 -04:00
|
|
|
|
2013-09-04 00:15:27 -03:00
|
|
|
// the UART thread runs at a medium priority
|
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 2048);
|
|
|
|
|
|
|
|
param.sched_priority = APM_UART_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
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
|
|
|
pthread_create(&_uart_thread_ctx, &thread_attr, &PX4Scheduler::_uart_thread, this);
|
2013-09-04 00:15:27 -03:00
|
|
|
|
2013-01-24 00:02:50 -04:00
|
|
|
// the IO thread runs at lower priority
|
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 2048);
|
2013-01-20 22:54:09 -04:00
|
|
|
|
2013-01-24 00:02:50 -04:00
|
|
|
param.sched_priority = APM_IO_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
2013-01-22 18:21:50 -04:00
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
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
|
|
|
pthread_create(&_io_thread_ctx, &thread_attr, &PX4Scheduler::_io_thread, this);
|
2015-03-04 05:07:11 -04:00
|
|
|
|
|
|
|
// the storage thread runs at just above IO priority
|
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 1024);
|
|
|
|
|
|
|
|
param.sched_priority = APM_STORAGE_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
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
|
|
|
pthread_create(&_storage_thread_ctx, &thread_attr, &PX4Scheduler::_storage_thread, this);
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
2013-10-13 18:29:30 -03:00
|
|
|
/**
|
|
|
|
delay for a specified number of microseconds using a semaphore wait
|
|
|
|
*/
|
|
|
|
void PX4Scheduler::delay_microseconds_semaphore(uint16_t usec)
|
|
|
|
{
|
|
|
|
sem_t wait_semaphore;
|
|
|
|
struct hrt_call wait_call;
|
|
|
|
sem_init(&wait_semaphore, 0, 0);
|
2015-02-12 20:51:20 -04:00
|
|
|
memset(&wait_call, 0, sizeof(wait_call));
|
2013-10-13 18:29:30 -03:00
|
|
|
hrt_call_after(&wait_call, usec, (hrt_callout)sem_post, &wait_semaphore);
|
|
|
|
sem_wait(&wait_semaphore);
|
|
|
|
}
|
|
|
|
|
2013-01-02 06:39:26 -04:00
|
|
|
void PX4Scheduler::delay_microseconds(uint16_t usec)
|
|
|
|
{
|
2013-10-13 18:29:30 -03:00
|
|
|
perf_begin(_perf_delay);
|
2015-02-12 20:51:20 -04:00
|
|
|
delay_microseconds_semaphore(usec);
|
2013-01-24 00:02:50 -04:00
|
|
|
perf_end(_perf_delay);
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
2015-02-15 20:53:08 -04:00
|
|
|
/*
|
|
|
|
wrapper around sem_post that boosts main thread priority
|
|
|
|
*/
|
|
|
|
static void sem_post_boost(sem_t *sem)
|
|
|
|
{
|
|
|
|
hal_px4_set_priority(APM_MAIN_PRIORITY_BOOST);
|
|
|
|
sem_post(sem);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return the main thread to normal priority
|
|
|
|
*/
|
|
|
|
static void set_normal_priority(void *sem)
|
|
|
|
{
|
|
|
|
hal_px4_set_priority(APM_MAIN_PRIORITY);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2016-05-12 14:01:14 -03:00
|
|
|
a variant of delay_microseconds that boosts priority to
|
2015-02-15 20:53:08 -04:00
|
|
|
APM_MAIN_PRIORITY_BOOST for APM_MAIN_PRIORITY_BOOST_USEC
|
|
|
|
microseconds when the time completes. This significantly improves
|
|
|
|
the regularity of timing of the main loop as it takes
|
|
|
|
*/
|
|
|
|
void PX4Scheduler::delay_microseconds_boost(uint16_t usec)
|
|
|
|
{
|
|
|
|
sem_t wait_semaphore;
|
|
|
|
static struct hrt_call wait_call;
|
|
|
|
sem_init(&wait_semaphore, 0, 0);
|
|
|
|
hrt_call_after(&wait_call, usec, (hrt_callout)sem_post_boost, &wait_semaphore);
|
|
|
|
sem_wait(&wait_semaphore);
|
|
|
|
hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, NULL);
|
|
|
|
}
|
|
|
|
|
2013-01-02 06:39:26 -04:00
|
|
|
void PX4Scheduler::delay(uint16_t ms)
|
|
|
|
{
|
2013-10-19 02:47:35 -03:00
|
|
|
if (in_timerprocess()) {
|
2013-01-22 18:21:50 -04:00
|
|
|
::printf("ERROR: delay() from timer process\n");
|
|
|
|
return;
|
|
|
|
}
|
2013-01-24 00:02:50 -04:00
|
|
|
perf_begin(_perf_delay);
|
2015-11-11 10:14:32 -04:00
|
|
|
uint64_t start = AP_HAL::micros64();
|
2013-01-02 06:39:26 -04:00
|
|
|
|
2015-11-11 10:14:32 -04:00
|
|
|
while ((AP_HAL::micros64() - start)/1000 < ms &&
|
2013-01-20 22:54:09 -04:00
|
|
|
!_px4_thread_should_exit) {
|
2013-10-13 18:29:30 -03:00
|
|
|
delay_microseconds_semaphore(1000);
|
2013-01-02 06:39:26 -04:00
|
|
|
if (_min_delay_cb_ms <= ms) {
|
|
|
|
if (_delay_cb) {
|
|
|
|
_delay_cb();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2013-01-24 00:02:50 -04:00
|
|
|
perf_end(_perf_delay);
|
2013-01-20 22:54:09 -04:00
|
|
|
if (_px4_thread_should_exit) {
|
|
|
|
exit(1);
|
|
|
|
}
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void PX4Scheduler::register_delay_callback(AP_HAL::Proc proc,
|
|
|
|
uint16_t min_time_ms)
|
|
|
|
{
|
|
|
|
_delay_cb = proc;
|
|
|
|
_min_delay_cb_ms = min_time_ms;
|
|
|
|
}
|
|
|
|
|
2013-09-30 07:36:19 -03:00
|
|
|
void PX4Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
2013-01-02 06:39:26 -04:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_timer_procs < PX4_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_timer_proc[_num_timer_procs] = proc;
|
|
|
|
_num_timer_procs++;
|
2013-01-20 22:54:09 -04:00
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of timer processes\n");
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-09-30 07:36:19 -03:00
|
|
|
void PX4Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
2013-04-17 08:33:50 -03:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
|
|
|
if (_io_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_io_procs < PX4_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_io_proc[_num_io_procs] = proc;
|
|
|
|
_num_io_procs++;
|
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of IO processes\n");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-09-30 07:36:19 -03:00
|
|
|
void PX4Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
2013-01-02 06:39:26 -04:00
|
|
|
{
|
2013-01-20 22:54:09 -04:00
|
|
|
_failsafe = failsafe;
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
2013-01-20 22:54:09 -04:00
|
|
|
void PX4Scheduler::suspend_timer_procs()
|
|
|
|
{
|
2013-01-02 06:39:26 -04:00
|
|
|
_timer_suspended = true;
|
|
|
|
}
|
|
|
|
|
2013-01-20 22:54:09 -04:00
|
|
|
void PX4Scheduler::resume_timer_procs()
|
|
|
|
{
|
2013-01-02 06:39:26 -04:00
|
|
|
_timer_suspended = false;
|
2013-01-20 22:54:09 -04:00
|
|
|
if (_timer_event_missed == true) {
|
|
|
|
_run_timers(false);
|
|
|
|
_timer_event_missed = false;
|
2013-01-02 06:45:17 -04:00
|
|
|
}
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
2013-09-03 22:58:13 -03:00
|
|
|
void PX4Scheduler::reboot(bool hold_in_bootloader)
|
2013-01-02 06:39:26 -04:00
|
|
|
{
|
2016-06-04 04:40:46 -03:00
|
|
|
// disarm motors to ensure they are off during a bootloader upload
|
|
|
|
hal.rcout->force_safety_on();
|
|
|
|
hal.rcout->force_safety_no_wait();
|
|
|
|
|
|
|
|
// delay to ensure the async force_saftey operation completes
|
|
|
|
delay(500);
|
|
|
|
|
2015-05-31 01:49:27 -03:00
|
|
|
px4_systemreset(hold_in_bootloader);
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
2013-01-20 22:54:09 -04:00
|
|
|
void PX4Scheduler::_run_timers(bool called_from_timer_thread)
|
2013-01-02 06:39:26 -04:00
|
|
|
{
|
|
|
|
if (_in_timer_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_timer_proc = true;
|
|
|
|
|
|
|
|
if (!_timer_suspended) {
|
|
|
|
// now call the timer based drivers
|
|
|
|
for (int i = 0; i < _num_timer_procs; i++) {
|
2015-05-26 00:54:38 -03:00
|
|
|
if (_timer_proc[i]) {
|
2013-09-30 07:36:19 -03:00
|
|
|
_timer_proc[i]();
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
}
|
2013-01-20 22:54:09 -04:00
|
|
|
} else if (called_from_timer_thread) {
|
|
|
|
_timer_event_missed = true;
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// and the failsafe, if one is setup
|
|
|
|
if (_failsafe != NULL) {
|
2013-09-30 07:36:19 -03:00
|
|
|
_failsafe();
|
2013-01-02 06:39:26 -04:00
|
|
|
}
|
|
|
|
|
2013-09-12 00:26:00 -03:00
|
|
|
// process analog input
|
|
|
|
((PX4AnalogIn *)hal.analogin)->_timer_tick();
|
|
|
|
|
2013-01-02 06:39:26 -04:00
|
|
|
_in_timer_proc = false;
|
|
|
|
}
|
|
|
|
|
2014-07-02 20:09:51 -03:00
|
|
|
extern bool px4_ran_overtime;
|
|
|
|
|
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
|
|
|
void *PX4Scheduler::_timer_thread(void *arg)
|
2013-01-20 22:54:09 -04:00
|
|
|
{
|
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
|
|
|
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
2014-07-02 20:09:51 -03:00
|
|
|
uint32_t last_ran_overtime = 0;
|
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
|
|
|
|
|
|
|
while (!sched->_hal_initialized) {
|
2013-10-26 04:12:35 -03:00
|
|
|
poll(NULL, 0, 1);
|
|
|
|
}
|
2013-01-20 22:54:09 -04:00
|
|
|
while (!_px4_thread_should_exit) {
|
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
|
|
|
sched->delay_microseconds_semaphore(1000);
|
2013-01-22 05:11:12 -04:00
|
|
|
|
|
|
|
// run registered timers
|
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
|
|
|
perf_begin(sched->_perf_timers);
|
|
|
|
sched->_run_timers(true);
|
|
|
|
perf_end(sched->_perf_timers);
|
2013-01-25 04:16:28 -04:00
|
|
|
|
|
|
|
// process any pending RC output requests
|
|
|
|
((PX4RCOutput *)hal.rcout)->_timer_tick();
|
2013-01-26 21:51:34 -04:00
|
|
|
|
|
|
|
// process any pending RC input requests
|
|
|
|
((PX4RCInput *)hal.rcin)->_timer_tick();
|
2014-07-02 20:09:51 -03:00
|
|
|
|
2015-11-11 10:14:32 -04:00
|
|
|
if (px4_ran_overtime && AP_HAL::millis() - last_ran_overtime > 2000) {
|
|
|
|
last_ran_overtime = AP_HAL::millis();
|
2016-05-24 23:35:42 -03:00
|
|
|
#if 0
|
2014-07-02 20:09:51 -03:00
|
|
|
printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
|
|
|
hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
2016-05-24 23:35:42 -03:00
|
|
|
#endif
|
2014-07-02 20:09:51 -03:00
|
|
|
}
|
2013-01-24 00:02:50 -04:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
2013-04-17 08:33:50 -03:00
|
|
|
void PX4Scheduler::_run_io(void)
|
|
|
|
{
|
|
|
|
if (_in_io_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_io_proc = true;
|
|
|
|
|
|
|
|
if (!_timer_suspended) {
|
|
|
|
// now call the IO based drivers
|
|
|
|
for (int i = 0; i < _num_io_procs; i++) {
|
2015-05-26 00:54:38 -03:00
|
|
|
if (_io_proc[i]) {
|
2013-09-30 07:36:19 -03:00
|
|
|
_io_proc[i]();
|
2013-04-17 08:33:50 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
_in_io_proc = false;
|
|
|
|
}
|
|
|
|
|
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
|
|
|
void *PX4Scheduler::_uart_thread(void *arg)
|
2013-01-24 00:02:50 -04:00
|
|
|
{
|
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
|
|
|
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
|
|
|
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
poll(NULL, 0, 1);
|
2013-10-26 04:12:35 -03:00
|
|
|
}
|
2013-01-24 00:02:50 -04:00
|
|
|
while (!_px4_thread_should_exit) {
|
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
|
|
|
sched->delay_microseconds_semaphore(1000);
|
2013-01-22 05:11:12 -04:00
|
|
|
|
|
|
|
// process any pending serial bytes
|
|
|
|
((PX4UARTDriver *)hal.uartA)->_timer_tick();
|
|
|
|
((PX4UARTDriver *)hal.uartB)->_timer_tick();
|
2013-02-17 22:55:33 -04:00
|
|
|
((PX4UARTDriver *)hal.uartC)->_timer_tick();
|
2013-11-22 04:16:51 -04:00
|
|
|
((PX4UARTDriver *)hal.uartD)->_timer_tick();
|
2013-12-21 07:25:15 -04:00
|
|
|
((PX4UARTDriver *)hal.uartE)->_timer_tick();
|
2016-04-19 00:47:56 -03:00
|
|
|
((PX4UARTDriver *)hal.uartF)->_timer_tick();
|
2013-09-04 00:15:27 -03:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
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
|
|
|
void *PX4Scheduler::_io_thread(void *arg)
|
2013-09-04 00:15:27 -03:00
|
|
|
{
|
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
|
|
|
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
|
|
|
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
poll(NULL, 0, 1);
|
2013-10-26 04:12:35 -03:00
|
|
|
}
|
2013-09-04 00:15:27 -03:00
|
|
|
while (!_px4_thread_should_exit) {
|
|
|
|
poll(NULL, 0, 1);
|
2013-01-23 01:37:11 -04:00
|
|
|
|
2013-04-17 08:33:50 -03:00
|
|
|
// run registered IO processes
|
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
|
|
|
perf_begin(sched->_perf_io_timers);
|
|
|
|
sched->_run_io();
|
|
|
|
perf_end(sched->_perf_io_timers);
|
2013-01-20 22:54:09 -04:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
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
|
|
|
void *PX4Scheduler::_storage_thread(void *arg)
|
2015-03-04 05:07:11 -04:00
|
|
|
{
|
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
|
|
|
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
|
|
|
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
poll(NULL, 0, 1);
|
2015-03-04 05:07:11 -04:00
|
|
|
}
|
|
|
|
while (!_px4_thread_should_exit) {
|
|
|
|
poll(NULL, 0, 10);
|
|
|
|
|
|
|
|
// process any pending storage writes
|
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
|
|
|
perf_begin(sched->_perf_storage_timer);
|
2015-03-04 05:07:11 -04:00
|
|
|
((PX4Storage *)hal.storage)->_timer_tick();
|
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
|
|
|
perf_end(sched->_perf_storage_timer);
|
2015-03-04 05:07:11 -04:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
2013-10-19 02:47:35 -03:00
|
|
|
bool PX4Scheduler::in_timerprocess()
|
|
|
|
{
|
|
|
|
return getpid() != _main_task_pid;
|
2013-01-10 21:20:43 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void PX4Scheduler::system_initialized() {
|
|
|
|
if (_initialized) {
|
2015-11-11 10:14:32 -04:00
|
|
|
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
2015-10-24 18:45:41 -03:00
|
|
|
"more than once");
|
2013-01-10 21:20:43 -04:00
|
|
|
}
|
|
|
|
_initialized = true;
|
|
|
|
}
|
|
|
|
|
2013-01-02 06:39:26 -04:00
|
|
|
#endif
|