mirror of https://github.com/ArduPilot/ardupilot
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);
^
This commit is contained in:
parent
036eb21c09
commit
6d7678d2a3
|
@ -22,21 +22,22 @@ extern const AP_HAL::HAL& hal;
|
|||
#include "Util.h"
|
||||
using namespace PX4;
|
||||
|
||||
void NSHShellStream::shell_thread(void)
|
||||
void NSHShellStream::shell_thread(void *arg)
|
||||
{
|
||||
NSHShellStream *nsh = (NSHShellStream *)arg;
|
||||
close(0);
|
||||
close(1);
|
||||
close(2);
|
||||
dup2(child.in, 0);
|
||||
dup2(child.out, 1);
|
||||
dup2(child.out, 2);
|
||||
dup2(nsh->child.in, 0);
|
||||
dup2(nsh->child.out, 1);
|
||||
dup2(nsh->child.out, 2);
|
||||
|
||||
nsh_consolemain(0, NULL);
|
||||
|
||||
shell_stdin = -1;
|
||||
shell_stdout = -1;
|
||||
child.in = -1;
|
||||
child.out = -1;
|
||||
nsh->shell_stdin = -1;
|
||||
nsh->shell_stdout = -1;
|
||||
nsh->child.in = -1;
|
||||
nsh->child.out = -1;
|
||||
}
|
||||
|
||||
void NSHShellStream::start_shell(void)
|
||||
|
|
|
@ -52,7 +52,7 @@ void PX4Scheduler::init()
|
|||
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
||||
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
||||
|
||||
pthread_create(&_timer_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_timer_thread, this);
|
||||
pthread_create(&_timer_thread_ctx, &thread_attr, &PX4Scheduler::_timer_thread, this);
|
||||
|
||||
// the UART thread runs at a medium priority
|
||||
pthread_attr_init(&thread_attr);
|
||||
|
@ -62,7 +62,7 @@ void PX4Scheduler::init()
|
|||
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
||||
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
||||
|
||||
pthread_create(&_uart_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_uart_thread, this);
|
||||
pthread_create(&_uart_thread_ctx, &thread_attr, &PX4Scheduler::_uart_thread, this);
|
||||
|
||||
// the IO thread runs at lower priority
|
||||
pthread_attr_init(&thread_attr);
|
||||
|
@ -72,7 +72,7 @@ void PX4Scheduler::init()
|
|||
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
||||
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
||||
|
||||
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
|
||||
pthread_create(&_io_thread_ctx, &thread_attr, &PX4Scheduler::_io_thread, this);
|
||||
|
||||
// the storage thread runs at just above IO priority
|
||||
pthread_attr_init(&thread_attr);
|
||||
|
@ -82,7 +82,7 @@ void PX4Scheduler::init()
|
|||
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
||||
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
||||
|
||||
pthread_create(&_storage_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_storage_thread, this);
|
||||
pthread_create(&_storage_thread_ctx, &thread_attr, &PX4Scheduler::_storage_thread, this);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -256,19 +256,21 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread)
|
|||
|
||||
extern bool px4_ran_overtime;
|
||||
|
||||
void *PX4Scheduler::_timer_thread(void)
|
||||
void *PX4Scheduler::_timer_thread(void *arg)
|
||||
{
|
||||
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
||||
uint32_t last_ran_overtime = 0;
|
||||
while (!_hal_initialized) {
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
delay_microseconds_semaphore(1000);
|
||||
sched->delay_microseconds_semaphore(1000);
|
||||
|
||||
// run registered timers
|
||||
perf_begin(_perf_timers);
|
||||
_run_timers(true);
|
||||
perf_end(_perf_timers);
|
||||
perf_begin(sched->_perf_timers);
|
||||
sched->_run_timers(true);
|
||||
perf_end(sched->_perf_timers);
|
||||
|
||||
// process any pending RC output requests
|
||||
((PX4RCOutput *)hal.rcout)->_timer_tick();
|
||||
|
@ -304,13 +306,15 @@ void PX4Scheduler::_run_io(void)
|
|||
_in_io_proc = false;
|
||||
}
|
||||
|
||||
void *PX4Scheduler::_uart_thread(void)
|
||||
void *PX4Scheduler::_uart_thread(void *arg)
|
||||
{
|
||||
while (!_hal_initialized) {
|
||||
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
delay_microseconds_semaphore(1000);
|
||||
sched->delay_microseconds_semaphore(1000);
|
||||
|
||||
// process any pending serial bytes
|
||||
((PX4UARTDriver *)hal.uartA)->_timer_tick();
|
||||
|
@ -322,34 +326,38 @@ void *PX4Scheduler::_uart_thread(void)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
void *PX4Scheduler::_io_thread(void)
|
||||
void *PX4Scheduler::_io_thread(void *arg)
|
||||
{
|
||||
while (!_hal_initialized) {
|
||||
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
poll(NULL, 0, 1);
|
||||
|
||||
// run registered IO processes
|
||||
perf_begin(_perf_io_timers);
|
||||
_run_io();
|
||||
perf_end(_perf_io_timers);
|
||||
perf_begin(sched->_perf_io_timers);
|
||||
sched->_run_io();
|
||||
perf_end(sched->_perf_io_timers);
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void *PX4Scheduler::_storage_thread(void)
|
||||
void *PX4Scheduler::_storage_thread(void *arg)
|
||||
{
|
||||
while (!_hal_initialized) {
|
||||
PX4Scheduler *sched = (PX4Scheduler *)arg;
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
poll(NULL, 0, 1);
|
||||
}
|
||||
while (!_px4_thread_should_exit) {
|
||||
poll(NULL, 0, 10);
|
||||
|
||||
// process any pending storage writes
|
||||
perf_begin(_perf_storage_timer);
|
||||
perf_begin(sched->_perf_storage_timer);
|
||||
((PX4Storage *)hal.storage)->_timer_tick();
|
||||
perf_end(_perf_storage_timer);
|
||||
perf_end(sched->_perf_storage_timer);
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -88,10 +88,10 @@ private:
|
|||
pthread_t _storage_thread_ctx;
|
||||
pthread_t _uart_thread_ctx;
|
||||
|
||||
void *_timer_thread(void);
|
||||
void *_io_thread(void);
|
||||
void *_storage_thread(void);
|
||||
void *_uart_thread(void);
|
||||
static void *_timer_thread(void *arg);
|
||||
static void *_io_thread(void *arg);
|
||||
static void *_storage_thread(void *arg);
|
||||
static void *_uart_thread(void *arg);
|
||||
|
||||
void _run_timers(bool called_from_timer_thread);
|
||||
void _run_io(void);
|
||||
|
|
|
@ -25,7 +25,7 @@ private:
|
|||
bool showed_armed_warning = false;
|
||||
|
||||
void start_shell(void);
|
||||
void shell_thread(void);
|
||||
static void shell_thread(void *arg);
|
||||
};
|
||||
|
||||
class PX4::PX4Util : public AP_HAL::Util {
|
||||
|
|
Loading…
Reference in New Issue