30 int32_t offs= hal_param_helper->_time_offset * 3600 * 1000;
47 memset(serialid, 0,
sizeof(serialid));
54 snprintf(buf, 40,
"%s %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
56 (
unsigned)serialid[0], (
unsigned)serialid[1], (
unsigned)serialid[2], (
unsigned)serialid[3],
57 (
unsigned)serialid[4], (
unsigned)serialid[5], (
unsigned)serialid[6], (
unsigned)serialid[7],
58 (
unsigned)serialid[8], (
unsigned)serialid[9], (
unsigned)serialid[10],(
unsigned)serialid[11]);
void set_soft_armed(const bool b)
void get_board_serial(uint8_t *serialid)
static void arming_state_changed(bool v)
void free_type(void *ptr, size_t size, Memory_Type mem_type) override
A system for managing and storing variables that are of general interest to the system.
bool run_debug_shell(AP_HAL::BetterStream *stream)
static uint64_t _micros64()
uint32_t available_memory(void) override
Semaphore * new_semaphore(void) override
uint64_t get_system_clock_ms() const
int snprintf(char *str, size_t size, const char *format,...)
void * malloc_type(size_t size, Memory_Type mem_type) override
bool get_system_id(char buf[40]) override
void set_system_clock(uint64_t time_utc_usec)