2013-01-21 02:10:42 -04:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_PX4_UTIL_H__
|
|
|
|
#define __AP_HAL_PX4_UTIL_H__
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-01-21 02:10:42 -04:00
|
|
|
#include "AP_HAL_PX4_Namespace.h"
|
|
|
|
|
2015-06-17 04:04:51 -03:00
|
|
|
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);
|
|
|
|
void shell_thread(void);
|
|
|
|
};
|
|
|
|
|
2013-01-21 02:10:42 -04:00
|
|
|
class PX4::PX4Util : public AP_HAL::Util {
|
|
|
|
public:
|
2013-10-05 02:47:28 -03:00
|
|
|
PX4Util(void);
|
2013-02-07 00:03:54 -04:00
|
|
|
bool run_debug_shell(AP_HAL::BetterStream *stream);
|
2013-10-05 02:47:28 -03:00
|
|
|
|
|
|
|
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);
|
|
|
|
|
2013-11-25 20:57:59 -04:00
|
|
|
/*
|
|
|
|
get system identifier (STM32 serial number)
|
|
|
|
*/
|
|
|
|
bool get_system_id(char buf[40]);
|
|
|
|
|
2013-12-28 01:01:28 -04:00
|
|
|
uint16_t available_memory(void);
|
|
|
|
|
2015-06-17 04:04:51 -03:00
|
|
|
/*
|
|
|
|
return a stream for access to nsh shell
|
|
|
|
*/
|
|
|
|
AP_HAL::Stream *get_shell_stream() { return &_shell_stream; }
|
|
|
|
|
2013-10-05 02:47:28 -03:00
|
|
|
private:
|
|
|
|
int _safety_handle;
|
2015-06-17 04:04:51 -03:00
|
|
|
PX4::NSHShellStream _shell_stream;
|
2013-01-21 02:10:42 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_PX4_UTIL_H__
|