APM:Libraries
I2CDevice.h
Go to the documentation of this file.
1 /*
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #pragma once
18 
19 #include <inttypes.h>
21 #include "Scheduler.h"
22 
23 #include <AP_HAL/HAL.h>
25 #include <AP_HAL/I2CDevice.h>
26 #include <AP_HAL/utility/OwnPtr.h>
27 #include "Semaphores.h"
28 
29 #include <i2c.h>
30 #include "tim_i2c.h"
31 
32 #define MAX_I2C_DEVICES 10
33 
34 using namespace F4Light;
35 
36 #ifdef I2C_DEBUG
37 enum I2C_Log_State {
38  I2C_START,
39  I2C_ISR,
40  I2C_STOP,
41  I2C_ERR,
42  I2C_FINISH,
43 };
44 
45 typedef struct I2C_STATE {
46  uint32_t time;
47  uint8_t addr;
48  uint8_t bus;
49  uint8_t send_len;
50  uint8_t recv_len;
51  uint8_t ret;
52  uint16_t cr1;
53  uint16_t sr1;
54  uint16_t sr2;
55  uint16_t st_sr1;
56  uint16_t st_sr2;
57  uint8_t state;
58  I2C_Log_State pos;
59 } I2C_State;
60 #endif
61 
62 
64 public:
65 
66  I2CDevice(uint8_t bus, uint8_t address);
67 
68  ~I2CDevice();
69 
70  static void lateInit();
71 
72  /* AP_HAL::I2CDevice implementation */
73 
74  /* See AP_HAL::I2CDevice::set_address() */
75  inline void set_address(uint8_t address) override { _address = address; }
76 
77  /* See AP_HAL::I2CDevice::set_retries() */
78  inline void set_retries(uint8_t retries) override { _retries = retries; }
79 
80 
81  /* AP_HAL::Device implementation */
82 
83  /* See AP_HAL::Device::transfer() */
84  bool transfer(const uint8_t *send, uint32_t send_len,
85  uint8_t *recv, uint32_t recv_len) override;
86 
87 
88  bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
89  uint32_t recv_len, uint8_t times);
90 
91 
92  /* See AP_HAL::Device::set_speed() */
93  inline bool set_speed(enum AP_HAL::Device::Speed speed) override { return true; };
94 
95  /* See AP_HAL::Device::get_semaphore() */
96  inline F4Light::Semaphore *get_semaphore() override { return &_semaphores[_bus]; } // numbers from 0
97 
98  /* See AP_HAL::Device::register_periodic_callback() */
100  uint32_t period_usec, Device::PeriodicCb proc) override
101  {
102  return Scheduler::register_timer_task(period_usec, proc, get_semaphore() );
103  }
104 
105 
107  AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
108  {
109  return Scheduler::adjust_timer_task(h, period_usec);
110  }
111 
113 
114  void register_completion_callback(Handler h);
115 
116  inline void register_completion_callback(AP_HAL::MemberProc proc){
117  Revo_handler r = { .mp=proc };
118  register_completion_callback(r.h);
119  }
121  Revo_handler r = { .hp=proc };
122  register_completion_callback(r.h);
123  }
124 
125  inline uint32_t get_error_count() { return _lockup_count; }
126  inline uint8_t get_last_error() { return last_error; }
127  inline uint8_t get_last_error_state() { return last_error_state; }
128  inline uint8_t get_bus() { return _bus; }
129  inline uint8_t get_addr() { return _address; }
130 
131  static inline uint8_t get_dev_count() { return dev_count; }
132  static inline F4Light::I2CDevice * get_device(uint8_t i) { return devices[i]; }
133 
134  void do_bus_reset();
135 
136 private:
137  void init();
138 
139  uint32_t i2c_read(uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen);
140  uint32_t i2c_write(uint8_t addr, const uint8_t *tx_buff, uint8_t len);
141  void isr_ev();
142  uint32_t wait_stop_done(bool v);
143  void finish_transfer();
144 
145  uint8_t _bus;
146  uint16_t _offs;
147  uint8_t _address;
148  uint8_t _retries;
149  uint32_t _lockup_count;
151  uint8_t last_error;
153  bool _slow;
154  bool _failed;
156  void *_task;
157 
158  const i2c_dev *_dev;
159  Soft_I2C *s_i2c; // per-bus instances
160 
161  static F4Light::Semaphore _semaphores[3]; // individual for each bus + softI2C
162  static const timer_dev * _timers[3]; // one timer per bus
163 
164  static F4Light::I2CDevice * devices[MAX_I2C_DEVICES]; // links to all created devices
165  static uint8_t dev_count;
166  static bool lateInitDone;
167 
169 
170  uint8_t _state; // state of transfer for ISR
171  volatile uint8_t _error; // error from ISR
172  uint8_t _addr; // data for ISR
173  const uint8_t *_tx_buff;
174  uint8_t _tx_len;
175  uint8_t *_rx_buff;
176  uint8_t _rx_len;
177 
178  void _do_bus_reset();
179 
180 #ifdef I2C_DEBUG
181 #define I2C_LOG_SIZE 99
182  static I2C_State log[I2C_LOG_SIZE];
183  static uint8_t log_ptr;
184 #endif
185 };
186 
188  friend class F4Light::I2CDevice;
189 
190 public:
192 
193  /* AP_HAL::I2CDeviceManager implementation */
195  uint8_t address,
196  uint32_t bus_clock=400000,
197  bool use_smbus = false,
198  uint32_t timeout_ms=4) {
199 
200  // let's first check for existence of such device on same bus
201  uint8_t n = I2CDevice::get_dev_count();
202 
203  for(uint8_t i=0; i<n; i++){
205  if(d){
206  if(d->get_bus() == bus && d->get_addr() == address) { // device already exists
207  return nullptr;
208  }
209  }
210  }
211 
213  new I2CDevice(bus, address)
214  );
215  }
216 };
217 
void register_completion_callback(AP_HAL::Proc proc)
Definition: I2CDevice.h:120
uint8_t get_last_error_state()
Definition: I2CDevice.h:127
AP_HAL::MemberProc mp
Definition: handler.h:18
#define MAX_I2C_DEVICES
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: I2CDevice.h:32
Handler h
Definition: handler.h:20
I2C device type.
Definition: i2c.h:100
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)
Definition: I2CDevice.h:194
uint32_t _lockup_count
Definition: I2CDevice.h:149
Soft_I2C * s_i2c
Definition: I2CDevice.h:159
uint32_t i2c_write(const i2c_dev *dev, uint8_t addr, const uint8_t *tx_buff, uint8_t txlen)
uint8_t last_error_state
Definition: I2CDevice.h:152
static uint8_t dev_count
Definition: I2CDevice.h:165
uint8_t * _rx_buff
Definition: I2CDevice.h:175
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: I2CDevice.h:106
void(* Proc)(void)
void register_completion_callback(AP_HAL::MemberProc proc)
Definition: I2CDevice.h:116
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
const i2c_dev * _dev
Definition: I2CDevice.h:158
void set_retries(uint8_t retries) override
Definition: I2CDevice.h:78
F4Light::Semaphore * get_semaphore() override
Definition: I2CDevice.h:96
volatile uint8_t _error
Definition: I2CDevice.h:171
static uint8_t get_dev_count()
Definition: I2CDevice.h:131
static AP_HAL::Device::PeriodicHandle register_timer_task(uint32_t period_us, AP_HAL::Device::PeriodicCb proc, F4Light::Semaphore *sem)
Definition: Scheduler.h:218
void * PeriodicHandle
Definition: Device.h:42
Handler _completion_cb
Definition: I2CDevice.h:168
static int state
Definition: Util.cpp:20
float v
Definition: Printf.cpp:15
bool unregister_callback(PeriodicHandle h) override
Definition: I2CDevice.h:112
void set_address(uint8_t address) override
Definition: I2CDevice.h:75
static bool adjust_timer_task(AP_HAL::Device::PeriodicHandle h, uint32_t period_us)
Definition: Scheduler.cpp:707
static bool unregister_timer_task(AP_HAL::Device::PeriodicHandle h)
Definition: Scheduler.cpp:718
static F4Light::I2CDevice * get_device(uint8_t i)
Definition: I2CDevice.h:132
uint32_t get_error_count()
Definition: I2CDevice.h:125
void init()
Generic board initialization function.
Definition: system.cpp:136
static bool lateInitDone
Definition: I2CDevice.h:166
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb proc) override
Definition: I2CDevice.h:99
uint64_t Handler
Definition: hal_types.h:19
const uint8_t * _tx_buff
Definition: I2CDevice.h:173
uint32_t i2c_read(const i2c_dev *dev, uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
uint8_t get_bus()
Definition: I2CDevice.h:128
uint8_t get_last_error()
Definition: I2CDevice.h:126
uint8_t get_addr()
Definition: I2CDevice.h:129
bool set_speed(enum AP_HAL::Device::Speed speed) override
Definition: I2CDevice.h:93
AP_HAL::Proc hp
Definition: handler.h:16
uint8_t last_error
Definition: I2CDevice.h:151