APM:Libraries
tim_i2c.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <stdbool.h>
4 #include <stm32f4xx.h>
5 #include <hal.h>
6 #include "systick.h"
7 #include "Scheduler.h"
8 #include "timer.h"
9 
10 //#define SI2C_DEBUG 1
11 //#define SI2C_PROF 1
12 
13 
14 
15 class Soft_I2C {
16 public:
17 
18  typedef enum STATE {
20  // address
39  // byte write
58 
62  RESTART2, // 2nd stage
64  // byte read after restart
83  } State;
84 
85 #ifdef SI2C_DEBUG
86  typedef struct SI2C_STATE {
87  uint32_t time;
88  State state;
89  unsigned int sda;
90  unsigned int f_sda;
91  } SI2C_State;
92 #endif
93 
94 
95 
96  Soft_I2C();
97 
98  void init();
99  void init_hw( const gpio_dev *scl_dev, uint8_t scl_bit, const gpio_dev *sda_dev, uint8_t sda_bit, const timer_dev *tim);
100 
101  uint8_t writeBuffer( uint8_t addr_, uint8_t len_, const uint8_t *data);
102  uint8_t read( uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf);
103  uint8_t transfer(uint8_t addr, uint8_t send_len, const uint8_t *send, uint8_t len, uint8_t *buf);
104 
105  bool bus_reset(void);
106 
107  void set_low_speed(bool s) { }
108 
109 
110 private:
111  void tick(); // ISR
112 
113  bool _start(void);
114  uint8_t wait_done();
115 
117  uint8_t _scl_bit;
119  uint8_t _sda_bit;
120  const timer_dev * _timer;
121 
122  volatile GPIO_TypeDef *scl_port; // for quick direct access to hardware
123  uint16_t scl_pin;
124  volatile GPIO_TypeDef *sda_port;
125  uint16_t sda_pin;
126 
127  volatile bool done;
128  volatile uint8_t result;
129  volatile State state;
130  bool f_sda; // what line we touch
131  bool wait_scl; // flag - we wait for SCL stretching
133 
134  uint8_t data; // data byte to output / from input
135 
136  const uint8_t *send;
137  uint8_t send_len;
138  uint8_t *recv;
139  uint8_t recv_len;
140  uint8_t _addr;
141 
142  uint16_t bit_time;
143 
144 #ifdef SI2C_DEBUG
145  #define SI2C_LOG_SIZE 199
146  static SI2C_State log[SI2C_LOG_SIZE];
147  static uint16_t log_ptr;
148 #endif
149 
150 #ifdef SI2C_PROF
151  static uint64_t full_time;
152  static uint32_t int_count;
153 #endif
154 
155 };
156 
uint8_t _addr
Definition: tim_i2c.h:140
enum Soft_I2C::STATE State
uint8_t read(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t *buf)
Definition: tim_i2c.cpp:532
uint8_t transfer(uint8_t addr, uint8_t send_len, const uint8_t *send, uint8_t len, uint8_t *buf)
Definition: tim_i2c.cpp:549
uint8_t _sda_bit
Definition: tim_i2c.h:119
void init_hw(const gpio_dev *scl_dev, uint8_t scl_bit, const gpio_dev *sda_dev, uint8_t sda_bit, const timer_dev *tim)
Definition: tim_i2c.cpp:114
const gpio_dev * _sda_dev
Definition: tim_i2c.h:118
bool was_restart
Definition: tim_i2c.h:132
const uint8_t * send
Definition: tim_i2c.h:136
timer interface.
void init()
Definition: tim_i2c.cpp:143
void tick()
Definition: tim_i2c.cpp:148
const gpio_dev * _scl_dev
Definition: tim_i2c.h:116
volatile State state
Definition: tim_i2c.h:129
uint8_t _scl_bit
Definition: tim_i2c.h:117
bool bus_reset(void)
Definition: tim_i2c.cpp:567
uint8_t recv_len
Definition: tim_i2c.h:139
bool wait_scl
Definition: tim_i2c.h:131
uint8_t data
Definition: tim_i2c.h:134
void set_low_speed(bool s)
Definition: tim_i2c.h:107
volatile GPIO_TypeDef * scl_port
Definition: tim_i2c.h:122
uint16_t sda_pin
Definition: tim_i2c.h:125
volatile bool done
Definition: tim_i2c.h:127
uint16_t scl_pin
Definition: tim_i2c.h:123
uint8_t wait_done()
Definition: tim_i2c.cpp:471
volatile uint8_t result
Definition: tim_i2c.h:128
bool _start(void)
Definition: tim_i2c.cpp:417
bool f_sda
Definition: tim_i2c.h:130
const timer_dev * _timer
Definition: tim_i2c.h:120
uint16_t bit_time
Definition: tim_i2c.h:142
Soft_I2C()
Definition: tim_i2c.cpp:106
volatile GPIO_TypeDef * sda_port
Definition: tim_i2c.h:124
uint8_t writeBuffer(uint8_t addr_, uint8_t len_, const uint8_t *data)
Definition: tim_i2c.cpp:516
uint8_t * recv
Definition: tim_i2c.h:138
uint8_t send_len
Definition: tim_i2c.h:137