ardupilot/libraries/AP_HAL_Linux/Util.h

53 lines
1.5 KiB
C
Raw Normal View History

2013-09-22 03:01:24 -03:00
#ifndef __AP_HAL_LINUX_UTIL_H__
#define __AP_HAL_LINUX_UTIL_H__
#include <AP_HAL/AP_HAL.h>
2013-09-22 03:01:24 -03:00
#include "AP_HAL_Linux_Namespace.h"
#include "ToneAlarmDriver.h"
class Linux::Util : public AP_HAL::Util {
2013-09-22 03:01:24 -03:00
public:
static Util *from(AP_HAL::Util *util) {
return static_cast<Util*>(util);
}
void init(int argc, char * const *argv);
2013-09-22 03:01:24 -03:00
bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; }
/**
return commandline arguments, if available
*/
void commandline_arguments(uint8_t &argc, char * const *&argv);
bool toneAlarm_init();
void toneAlarm_set_tune(uint8_t tune);
void _toneAlarm_timer_tick();
2015-01-19 13:30:18 -04:00
/*
set system clock in UTC microseconds
*/
void set_system_clock(uint64_t time_utc_usec);
const char* get_custom_log_directory() { return custom_log_directory; }
const char* get_custom_terrain_directory() { return custom_terrain_directory; }
void set_custom_log_directory(const char *_custom_log_directory) { custom_log_directory = _custom_log_directory; }
void set_custom_terrain_directory(const char *_custom_terrain_directory) { custom_terrain_directory = _custom_terrain_directory; }
2015-01-19 13:30:18 -04:00
bool is_chardev_node(const char *path);
void set_imu_temp(float current);
private:
static Linux::ToneAlarm _toneAlarm;
Linux::Heat *_heat;
int saved_argc;
char* const *saved_argv;
const char* custom_log_directory = NULL;
const char* custom_terrain_directory = NULL;
2013-09-22 03:01:24 -03:00
};
2013-09-22 03:01:24 -03:00
#endif // __AP_HAL_LINUX_UTIL_H__