2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-11-05 23:46:33 -04:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-11-05 23:46:33 -04:00
|
|
|
|
2013-09-22 03:01:24 -03:00
|
|
|
#include "AP_HAL_Linux_Namespace.h"
|
2014-11-15 01:51:21 -04:00
|
|
|
#include "ToneAlarmDriver.h"
|
2015-12-16 17:24:11 -04:00
|
|
|
#include "Semaphores.h"
|
2014-08-23 04:52:43 -03:00
|
|
|
|
2015-12-22 09:49:12 -04:00
|
|
|
enum hw_type {
|
|
|
|
UTIL_HARDWARE_RPI1 = 0,
|
|
|
|
UTIL_HARDWARE_RPI2,
|
|
|
|
UTIL_HARDWARE_BEBOP,
|
|
|
|
UTIL_HARDWARE_BEBOP2,
|
|
|
|
UTIL_NUM_HARDWARES,
|
|
|
|
};
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
class Linux::Util : public AP_HAL::Util {
|
2013-09-22 03:01:24 -03:00
|
|
|
public:
|
2015-10-20 18:13:25 -03:00
|
|
|
static Util *from(AP_HAL::Util *util) {
|
|
|
|
return static_cast<Util*>(util);
|
2015-09-13 15:28:02 -03:00
|
|
|
}
|
|
|
|
|
2015-09-25 11:07:59 -03:00
|
|
|
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; }
|
2014-02-22 17:15:39 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
return commandline arguments, if available
|
|
|
|
*/
|
|
|
|
void commandline_arguments(uint8_t &argc, char * const *&argv);
|
|
|
|
|
2014-11-15 01:51:21 -04:00
|
|
|
bool toneAlarm_init();
|
2014-08-23 04:52:43 -03:00
|
|
|
void toneAlarm_set_tune(uint8_t tune);
|
2015-12-22 09:49:12 -04:00
|
|
|
|
2014-08-23 04:52:43 -03:00
|
|
|
void _toneAlarm_timer_tick();
|
2014-11-15 01:51:21 -04:00
|
|
|
|
2015-01-19 13:30:18 -04:00
|
|
|
/*
|
|
|
|
set system clock in UTC microseconds
|
|
|
|
*/
|
2015-06-28 16:10:33 -03:00
|
|
|
void set_system_clock(uint64_t time_utc_usec);
|
2015-06-29 22:42:30 -03:00
|
|
|
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
|
|
|
|
2015-06-27 18:18:09 -03:00
|
|
|
bool is_chardev_node(const char *path);
|
2015-09-25 11:07:59 -03:00
|
|
|
void set_imu_temp(float current);
|
2015-06-27 18:18:09 -03:00
|
|
|
|
2015-11-05 01:06:15 -04:00
|
|
|
uint32_t available_memory(void) override;
|
2015-10-01 18:19:15 -03:00
|
|
|
|
2015-11-05 23:46:33 -04:00
|
|
|
/*
|
|
|
|
* Write a string as specified by @fmt to the file in @path. Note this
|
|
|
|
* should not be used on hot path since it will open, write and close the
|
|
|
|
* file for each call.
|
|
|
|
*/
|
2015-11-10 13:05:19 -04:00
|
|
|
int write_file(const char *path, const char *fmt, ...) FMT_PRINTF(3, 4);
|
2015-11-05 23:46:33 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
* Read a string as specified by @fmt from the file in @path. Note this
|
|
|
|
* should not be used on hot path since it will open, read and close the
|
|
|
|
* file for each call.
|
|
|
|
*/
|
|
|
|
int read_file(const char *path, const char *fmt, ...) FMT_SCANF(3, 4);
|
2015-10-01 18:19:15 -03:00
|
|
|
|
2015-11-03 12:13:03 -04:00
|
|
|
perf_counter_t perf_alloc(perf_counter_type t, const char *name) override;
|
|
|
|
void perf_begin(perf_counter_t perf) override;
|
|
|
|
void perf_end(perf_counter_t perf) override;
|
|
|
|
void perf_count(perf_counter_t perf) override;
|
|
|
|
|
2015-12-16 17:24:11 -04:00
|
|
|
// create a new semaphore
|
|
|
|
AP_HAL::Semaphore *new_semaphore(void) override { return new Linux::Semaphore; }
|
2015-12-22 09:49:12 -04:00
|
|
|
|
|
|
|
int get_hw_arm32();
|
|
|
|
|
2014-11-15 01:51:21 -04:00
|
|
|
private:
|
2015-06-28 16:10:33 -03:00
|
|
|
static Linux::ToneAlarm _toneAlarm;
|
2015-10-20 18:13:25 -03:00
|
|
|
Linux::Heat *_heat;
|
2014-02-22 17:15:39 -04:00
|
|
|
int saved_argc;
|
|
|
|
char* const *saved_argv;
|
2015-06-29 22:42:30 -03:00
|
|
|
const char* custom_log_directory = NULL;
|
2015-12-22 09:49:12 -04:00
|
|
|
const char* custom_terrain_directory = NULL;
|
|
|
|
static const char *_hw_names[UTIL_NUM_HARDWARES];
|
2013-09-22 03:01:24 -03:00
|
|
|
};
|