APM:Libraries
HAL_F4Light_Class.h
Go to the documentation of this file.
1 
2 #pragma once
3 
4 
5 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
6 
8 #include "handler.h"
9 
10 #include <AP_Param/AP_Param.h>
11 
12 #include <hal.h>
13 #include "USBDriver.h"
14 #include <pwm_in.h>
15 #include <usart.h>
16 #include <i2c.h>
17 #include <spi.h>
18 
19 
20 #if defined(USB_MASSSTORAGE)
22 #endif
23 
24 /*
25 Backup SRAM 4KByte - 0x4002 4000 - 0x4002 3FFF can be used as EEPROM buffer?
26 
27 ideally it should be used for state storage for recovery from in-flight reboots but we never get this from upstream...
28 
29 */
30 
31 
32 class HAL_state{
33 public:
35  : sd_busy(0)
36  , disconnect(0)
37  {}
38 
39  uint8_t sd_busy;
40  uint8_t disconnect;
41 };
42 
43 class HAL_F4Light : public AP_HAL::HAL {
44 public:
45  HAL_F4Light();
46  void run(int argc, char * const argv[], Callbacks* callbacks) const override;
47 
48  void lateInit();
49 
50  static HAL_state state; // hal is const so we should move out its internal state
51 
52 private:
53  AP_HAL::UARTDriver** uarts[6];
54 
55  void connect_uart(AP_HAL::UARTDriver* uartL,AP_HAL::UARTDriver* uartR, AP_HAL::Proc proc);
56  // parameters in hal_param_helper
57 
58 #if defined(USB_MASSSTORAGE)
59  F4Light::MassStorage massstorage;
60 #endif
61 
62 };
63 
64 
65 #endif // __AP_HAL_F4Light_CLASS_H__
void(* Proc)(void)
uint8_t disconnect
static HAL_state state
A system for managing and storing variables that are of general interest to the system.
uint8_t sd_busy