ardupilot/libraries/AP_HAL_PX4/Util.h

65 lines
1.6 KiB
C
Raw Normal View History

#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_PX4_Namespace.h"
2015-12-19 17:35:13 -04:00
#include "Semaphores.h"
class PX4::NSHShellStream : public AP_HAL::Stream {
public:
size_t write(uint8_t);
size_t write(const uint8_t *buffer, size_t size);
int16_t read();
int16_t available();
int16_t txspace();
private:
int shell_stdin = -1;
int shell_stdout = -1;
pthread_t shell_thread_ctx;
struct {
int in = -1;
int out = -1;
} child;
bool showed_memory_warning = false;
bool showed_armed_warning = false;
void start_shell(void);
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 shell_thread(void *arg);
};
class PX4::PX4Util : public AP_HAL::Util {
public:
PX4Util(void);
bool run_debug_shell(AP_HAL::BetterStream *stream);
enum safety_state safety_switch_state(void);
2013-10-23 09:26:55 -03:00
/*
set system clock in UTC microseconds
*/
void set_system_clock(uint64_t time_utc_usec);
/*
get system identifier (STM32 serial number)
*/
bool get_system_id(char buf[40]);
uint32_t available_memory(void) override;
2013-12-28 01:01:28 -04:00
/*
return a stream for access to nsh shell
*/
AP_HAL::Stream *get_shell_stream() { return &_shell_stream; }
perf_counter_t perf_alloc(perf_counter_type t, const char *name) override;
void perf_begin(perf_counter_t ) override;
void perf_end(perf_counter_t) override;
void perf_count(perf_counter_t) override;
2015-12-19 17:35:13 -04:00
// create a new semaphore
AP_HAL::Semaphore *new_semaphore(void) override { return new PX4::Semaphore; }
private:
int _safety_handle;
PX4::NSHShellStream _shell_stream;
};