2012-12-18 20:09:24 -04:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_UTIL_H__
|
|
|
|
#define __AP_HAL_UTIL_H__
|
|
|
|
|
|
|
|
#include <stdarg.h>
|
|
|
|
#include "AP_HAL_Namespace.h"
|
|
|
|
|
|
|
|
class AP_HAL::Util {
|
|
|
|
public:
|
2013-09-21 00:28:46 -03:00
|
|
|
int snprintf(char* str, size_t size,
|
|
|
|
const char *format, ...);
|
2012-12-18 20:09:24 -04:00
|
|
|
|
2013-09-21 00:28:46 -03:00
|
|
|
int vsnprintf(char* str, size_t size,
|
|
|
|
const char *format, va_list ap);
|
2012-12-18 20:09:24 -04:00
|
|
|
|
2015-01-28 19:15:48 -04:00
|
|
|
void set_soft_armed(const bool b) { soft_armed = b; }
|
|
|
|
bool get_soft_armed() const { return soft_armed; }
|
|
|
|
|
2015-07-30 03:40:36 -03:00
|
|
|
void set_capabilities(uint64_t cap) { capabilities |= cap; }
|
|
|
|
void clear_capabilities(uint64_t cap) { capabilities &= ~(cap); }
|
|
|
|
uint64_t get_capabilities() const { return capabilities; }
|
|
|
|
|
2015-06-28 16:09:20 -03:00
|
|
|
virtual const char* get_custom_log_directory() { return NULL; }
|
|
|
|
virtual const char* get_custom_terrain_directory() const { return NULL; }
|
|
|
|
|
2016-01-06 18:09:09 -04:00
|
|
|
// get path to custom defaults file for AP_Param
|
|
|
|
virtual const char* get_custom_defaults_file() const {
|
|
|
|
return HAL_PARAM_DEFAULTS_PATH;
|
|
|
|
}
|
|
|
|
|
2013-02-07 00:03:34 -04:00
|
|
|
// run a debug shall on the given stream if possible. This is used
|
|
|
|
// to support dropping into a debug shell to run firmware upgrade
|
|
|
|
// commands
|
|
|
|
virtual bool run_debug_shell(AP_HAL::BetterStream *stream) = 0;
|
|
|
|
|
2013-10-05 02:46:35 -03:00
|
|
|
enum safety_state {
|
|
|
|
SAFETY_NONE, SAFETY_DISARMED, SAFETY_ARMED
|
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
return state of safety switch, if applicable
|
|
|
|
*/
|
|
|
|
virtual enum safety_state safety_switch_state(void) { return SAFETY_NONE; }
|
2013-10-23 09:26:36 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
set system clock in UTC microseconds
|
|
|
|
*/
|
|
|
|
virtual void set_system_clock(uint64_t time_utc_usec) {}
|
2013-11-25 20:57:40 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
get system identifier (eg. serial number)
|
|
|
|
return false if a system identifier is not available
|
|
|
|
|
|
|
|
Buf should be filled with a printable string and must be null
|
|
|
|
terminated
|
|
|
|
*/
|
|
|
|
virtual bool get_system_id(char buf[40]) { return false; }
|
2013-12-27 23:51:01 -04:00
|
|
|
|
|
|
|
/**
|
2015-11-05 00:41:13 -04:00
|
|
|
how much free memory do we have in bytes. If unknown return 4096
|
2013-12-27 23:51:01 -04:00
|
|
|
*/
|
2015-11-05 00:41:13 -04:00
|
|
|
virtual uint32_t available_memory(void) { return 4096; }
|
2014-02-22 17:15:39 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
return commandline arguments, if available
|
|
|
|
*/
|
|
|
|
virtual void commandline_arguments(uint8_t &argc, char * const *&argv) { argc = 0; }
|
2014-08-23 04:56:24 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
ToneAlarm Driver
|
|
|
|
*/
|
2014-11-15 01:50:07 -04:00
|
|
|
virtual bool toneAlarm_init() { return false;}
|
2014-08-23 04:56:24 -03:00
|
|
|
virtual void toneAlarm_set_tune(uint8_t tune) {}
|
|
|
|
virtual void _toneAlarm_timer_tick() {}
|
2015-01-28 19:15:48 -04:00
|
|
|
|
2015-06-17 04:04:15 -03:00
|
|
|
/*
|
|
|
|
return a stream for access to a system shell, if available
|
|
|
|
*/
|
|
|
|
virtual AP_HAL::Stream *get_shell_stream() { return NULL; }
|
|
|
|
|
2015-10-02 06:29:27 -03:00
|
|
|
/* Support for an imu heating system */
|
|
|
|
virtual void set_imu_temp(float current) {}
|
|
|
|
|
2015-10-20 02:41:52 -03:00
|
|
|
/*
|
|
|
|
performance counter calls - wrapper around original PX4 interface
|
|
|
|
*/
|
|
|
|
enum perf_counter_type {
|
|
|
|
PC_COUNT, /**< count the number of times an event occurs */
|
|
|
|
PC_ELAPSED, /**< measure the time elapsed performing an event */
|
|
|
|
PC_INTERVAL /**< measure the interval between instances of an event */
|
|
|
|
};
|
|
|
|
typedef void *perf_counter_t;
|
|
|
|
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return NULL; }
|
|
|
|
virtual void perf_begin(perf_counter_t h) {}
|
|
|
|
virtual void perf_end(perf_counter_t h) {}
|
|
|
|
virtual void perf_count(perf_counter_t h) {}
|
2015-12-16 17:23:57 -04:00
|
|
|
|
|
|
|
// create a new semaphore
|
|
|
|
virtual Semaphore *new_semaphore(void) { return nullptr; }
|
2015-10-20 02:41:52 -03:00
|
|
|
|
2015-01-28 19:15:48 -04:00
|
|
|
protected:
|
2015-08-22 05:47:45 -03:00
|
|
|
// we start soft_armed false, so that actuators don't send any
|
|
|
|
// values until the vehicle code has fully started
|
|
|
|
bool soft_armed = false;
|
|
|
|
uint64_t capabilities = 0;
|
2012-12-18 20:09:24 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_UTIL_H__
|
|
|
|
|