APM:Libraries
AP_IOMCU.h
Go to the documentation of this file.
1 /*
2  implement protocol for controlling an IO microcontroller
3 
4  For bootstrapping this will initially implement the px4io protocol,
5  but will later move to an ArduPilot specific protocol
6  */
7 
8 #include <AP_HAL/AP_HAL.h>
9 
10 #if HAL_WITH_IO_MCU
11 
12 #include "ch.h"
13 
14 #define IOMCU_MAX_CHANNELS 16
15 
16 class AP_IOMCU {
17 public:
18  AP_IOMCU(AP_HAL::UARTDriver &uart);
19 
20  void init(void);
21 
22  // write to one channel
23  void write_channel(uint8_t chan, uint16_t pwm);
24 
25  // read from one channel
26  uint16_t read_channel(uint8_t chan);
27 
28  // cork output
29  void cork(void);
30 
31  // push output
32  void push(void);
33 
34  // set output frequency
35  void set_freq(uint16_t chmask, uint16_t freq);
36 
37  // get output frequency
38  uint16_t get_freq(uint16_t chan);
39 
40  // get state of safety switch
41  AP_HAL::Util::safety_state get_safety_switch_state(void) const;
42 
43  // force safety on
44  bool force_safety_on(void);
45 
46  // force safety off
47  void force_safety_off(void);
48 
49  // set PWM of channels when safety is on
50  void set_safety_pwm(uint16_t chmask, uint16_t period_us);
51 
52  // set mask of channels that ignore safety state
53  void set_safety_mask(uint16_t chmask);
54 
55  /*
56  enable sbus output
57  */
58  bool enable_sbus_out(uint16_t rate_hz);
59 
60  /*
61  check for new RC input
62  */
63  bool check_rcinput(uint32_t &last_frame_us, uint8_t &num_channels, uint16_t *channels, uint8_t max_channels);
64 
65  /*
66  get servo rail voltage
67  */
68  float get_vservo(void) const { return reg_status.vservo * 0.001; }
69 
70  /*
71  get rssi voltage
72  */
73  float get_vrssi(void) const { return reg_status.vrssi * 0.001; }
74 
75  // set target for IMU heater
76  void set_heater_duty_cycle(uint8_t duty_cycle);
77 
78  // set default output rate
79  void set_default_rate(uint16_t rate_hz);
80 
81  // set to oneshot mode
82  void set_oneshot_mode(void);
83 
84  // check if IO is healthy
85  bool healthy(void);
86 
87 private:
88  AP_HAL::UARTDriver &uart;
89 
90  static void thread_start(void *ctx);
91  void thread_main(void);
92 
93  // read count 16 bit registers
94  bool read_registers(uint8_t page, uint8_t offset, uint8_t count, uint16_t *regs);
95 
96  // write count 16 bit registers
97  bool write_registers(uint8_t page, uint8_t offset, uint8_t count, const uint16_t *regs);
98 
99  // write a single register
100  bool write_register(uint8_t page, uint8_t offset, uint16_t v) {
101  return write_registers(page, offset, 1, &v);
102  }
103 
104  // modify a single register
105  bool modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits);
106 
107  // trigger an ioevent
108  void trigger_event(uint8_t event);
109 
110  // IOMCU thread
111  thread_t *thread_ctx;
112 
113  // time when we last read various pages
114  uint32_t last_status_read_ms;
115  uint32_t last_rc_read_ms;
116  uint32_t last_servo_read_ms;
117  uint32_t last_debug_ms;
118  uint32_t last_safety_option_check_ms;
119 
120  // last value of safety options
121  uint16_t last_safety_options = 0xFFFF;
122 
123  void send_servo_out(void);
124  void read_rc_input(void);
125  void read_servo(void);
126  void read_status(void);
127  void print_debug(void);
128  void discard_input(void);
129  void event_failed(uint8_t event);
130  void update_safety_options(void);
131 
132  // PAGE_STATUS values
133  struct PACKED {
134  uint16_t freemem;
135  uint16_t cpuload;
136 
137  // status flags
138  uint16_t flag_outputs_armed:1;
139  uint16_t flag_override:1;
140  uint16_t flag_rc_ok:1;
141  uint16_t flag_rc_ppm:1;
142  uint16_t flag_rc_dsm:1;
143  uint16_t flag_rc_sbus:1;
144  uint16_t flag_fmu_ok:1;
145  uint16_t flag_raw_pwm:1;
146  uint16_t flag_mixer_ok:1;
147  uint16_t flag_arm_sync:1;
148  uint16_t flag_init_ok:1;
149  uint16_t flag_failsafe:1;
150  uint16_t flag_safety_off:1;
151  uint16_t flag_fmu_initialised:1;
152  uint16_t flag_rc_st24:1;
153  uint16_t flag_rc_sumd_srxl:1;
154 
155  uint16_t alarms;
156  uint16_t vbatt;
157  uint16_t ibatt;
158  uint16_t vservo;
159  uint16_t vrssi;
160  uint16_t prssi;
161  } reg_status;
162 
163  // PAGE_RAW_RCIN values
164  struct PACKED {
165  uint16_t count;
166  uint16_t flags_frame_drop:1;
167  uint16_t flags_failsafe:1;
168  uint16_t flags_dsm11:1;
169  uint16_t flags_mapping_ok:1;
170  uint16_t flags_rc_ok:1;
171  uint16_t flags_unused:11;
172  uint16_t nrssi;
173  uint16_t data;
174  uint16_t frame_count;
175  uint16_t lost_frame_count;
176  uint16_t pwm[IOMCU_MAX_CHANNELS];
177  uint16_t last_frame_count;
178  uint32_t last_input_us;
179  } rc_input;
180 
181  // output pwm values
182  struct {
183  uint8_t num_channels;
184  uint16_t pwm[IOMCU_MAX_CHANNELS];
185  uint8_t safety_pwm_set;
186  uint8_t safety_pwm_sent;
187  uint16_t safety_pwm[IOMCU_MAX_CHANNELS];
188  uint16_t safety_mask;
189  } pwm_out;
190 
191  // read back pwm values
192  struct {
193  uint16_t pwm[IOMCU_MAX_CHANNELS];
194  } pwm_in;
195 
196  // output rates
197  struct {
198  uint16_t freq;
199  uint16_t chmask;
200  uint16_t default_freq = 50;
201  uint16_t sbus_rate_hz;
202  } rate;
203 
204  // IMU heater duty cycle
205  uint8_t heater_duty_cycle;
206 
207  uint32_t last_servo_out_us;
208 
209  bool corked;
210 
211  bool crc_is_ok;
212 
213  // firmware upload
214  const char *fw_name = "io_firmware.bin";
215  const uint8_t *fw;
216 
217  bool upload_fw(const char *filename);
218  bool recv_byte_with_timeout(uint8_t *c, uint32_t timeout_ms);
219  bool recv_bytes(uint8_t *p, uint32_t count);
220  void drain(void);
221  bool send(uint8_t c);
222  bool send(const uint8_t *p, uint32_t count);
223  bool get_sync(uint32_t timeout = 40);
224  bool sync();
225  bool get_info(uint8_t param, uint32_t &val);
226  bool erase();
227  bool program(uint32_t fw_size);
228  bool verify_rev2(uint32_t fw_size);
229  bool verify_rev3(uint32_t fw_size_local);
230  bool reboot();
231 
232  bool check_crc(void);
233 
234  enum {
235  PROTO_NOP = 0x00,
236  PROTO_OK = 0x10,
237  PROTO_FAILED = 0x11,
238  PROTO_INSYNC = 0x12,
239  PROTO_INVALID = 0x13,
240  PROTO_BAD_SILICON_REV = 0x14,
241  PROTO_EOC = 0x20,
242  PROTO_GET_SYNC = 0x21,
243  PROTO_GET_DEVICE = 0x22,
244  PROTO_CHIP_ERASE = 0x23,
245  PROTO_CHIP_VERIFY = 0x24,
246  PROTO_PROG_MULTI = 0x27,
247  PROTO_READ_MULTI = 0x28,
248  PROTO_GET_CRC = 0x29,
249  PROTO_GET_OTP = 0x2a,
250  PROTO_GET_SN = 0x2b,
251  PROTO_GET_CHIP = 0x2c,
252  PROTO_SET_DELAY = 0x2d,
253  PROTO_GET_CHIP_DES = 0x2e,
254  PROTO_REBOOT = 0x30,
255 
256  INFO_BL_REV = 1,
257  BL_REV = 5,
258  INFO_BOARD_ID = 2,
259  INFO_BOARD_REV = 3,
260  INFO_FLASH_SIZE = 4,
262  PROG_MULTI_MAX = 248,
263  };
264 };
265 
266 #endif // HAL_WITH_IO_MCU
static uint16_t pwm
Definition: RCOutput.cpp:20
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
static uint8_t max_channels
void sync(void)
POSIX Sync all pending file changes and metadata on ALL files.
Definition: posix.c:1058
float v
Definition: Printf.cpp:15
safety_state
Definition: Util.h:35
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void init()
Generic board initialization function.
Definition: system.cpp:136
#define PACKED
Definition: AP_Common.h:28