Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
softi2c.c
Go to the documentation of this file.
1/*
2 * Copyright (C) 2020 Tom van Dijk <tomvand@users.noreply.github.com>
3 *
4 * This file is part of paparazzi.
5 *
6 * paparazzi is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License as published by
8 * the Free Software Foundation; either version 2, or (at your option)
9 * any later version.
10 *
11 * paparazzi is distributed in the hope that it will be useful,
12 * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 * GNU General Public License for more details.
15 *
16 * You should have received a copy of the GNU General Public License
17 * along with paparazzi; see the file COPYING. If not, write to
18 * the Free Software Foundation, 59 Temple Place - Suite 330,
19 * Boston, MA 02111-1307, USA.
20 *
21 */
22
31#include "mcu_periph/softi2c.h"
32
33#include "mcu_arch.h"
34#include "mcu_periph/gpio.h"
35#include "mcu_periph/sys_time.h"
36
37#if PERIODIC_TELEMETRY
39#endif
40
41#include <stdbool.h>
42
43
44#ifndef SOFTI2C0_DIVIDER
45#define SOFTI2C0_DIVIDER 1
46#endif
47#ifndef SOFTI2C1_DIVIDER
48#define SOFTI2C1_DIVIDER 1
49#endif
50
51
58 /* Bit-level state machine */
60 /* Byte-level state machine */
62 /* Transaction-level state machine */
63 // periph->status
64 // periph->idx_buf
65};
66
67
68static bool softi2c_idle(struct i2c_periph *periph) __attribute__((unused));
69static bool softi2c_submit(struct i2c_periph *periph, struct i2c_transaction *t) __attribute__((unused));
70static void softi2c_setbitrate(struct i2c_periph *periph, int bitrate) __attribute__((unused));
71static void softi2c_spin(struct i2c_periph *p) __attribute__((unused));
72
73
74#if USE_SOFTI2C0 && ( \
75 !defined(SOFTI2C0_SDA_GPIO) || !defined(SOFTI2C0_SDA_PIN) || \
76 !defined(SOFTI2C0_SCL_GPIO) || !defined(SOFTI2C0_SCL_PIN))
77#error "SDA and SCL pins must be configured for SOFTI2C0!"
78#endif
79
80#if USE_SOFTI2C1 && ( \
81 !defined(SOFTI2C1_SDA_GPIO) || !defined(SOFTI2C1_SDA_PIN) || \
82 !defined(SOFTI2C1_SCL_GPIO) || !defined(SOFTI2C1_SCL_PIN))
83#error "SDA and SCL pins must be configured for SOFTI2C1!"
84#endif
85
86
87#if USE_SOFTI2C0
88struct i2c_periph softi2c0;
90void softi2c0_init(void) {
93}
94#if PERIODIC_TELEMETRY
95void send_softi2c0_err(struct transport_tx *trans, struct link_device *dev)
96{
97 uint16_t i2c0_wd_reset_cnt = softi2c0.errors->wd_reset_cnt;
98 uint16_t i2c0_queue_full_cnt = softi2c0.errors->queue_full_cnt;
99 uint16_t i2c0_ack_fail_cnt = softi2c0.errors->ack_fail_cnt;
100 uint16_t i2c0_miss_start_stop_cnt = softi2c0.errors->miss_start_stop_cnt;
101 uint16_t i2c0_arb_lost_cnt = softi2c0.errors->arb_lost_cnt;
102 uint16_t i2c0_over_under_cnt = softi2c0.errors->over_under_cnt;
103 uint16_t i2c0_pec_recep_cnt = softi2c0.errors->pec_recep_cnt;
104 uint16_t i2c0_timeout_tlow_cnt = softi2c0.errors->timeout_tlow_cnt;
105 uint16_t i2c0_smbus_alert_cnt = softi2c0.errors->smbus_alert_cnt;
106 uint16_t i2c0_unexpected_event_cnt = softi2c0.errors->unexpected_event_cnt;
107 uint32_t i2c0_last_unexpected_event = softi2c0.errors->last_unexpected_event;
108 uint8_t _bus0 = 10;
121 &_bus0);
122}
123#endif
124#endif /* USE_SOFTI2C0 */
125
126#if USE_SOFTI2C1
127struct i2c_periph softi2c1;
128static struct softi2c_device softi2c1_device;
129void softi2c1_init(void) {
132}
133#if PERIODIC_TELEMETRY
134void send_softi2c1_err(struct transport_tx *trans, struct link_device *dev)
135{
136 uint16_t i2c1_wd_reset_cnt = softi2c1.errors->wd_reset_cnt;
137 uint16_t i2c1_queue_full_cnt = softi2c1.errors->queue_full_cnt;
138 uint16_t i2c1_ack_fail_cnt = softi2c1.errors->ack_fail_cnt;
139 uint16_t i2c1_miss_start_stop_cnt = softi2c1.errors->miss_start_stop_cnt;
140 uint16_t i2c1_arb_lost_cnt = softi2c1.errors->arb_lost_cnt;
141 uint16_t i2c1_over_under_cnt = softi2c1.errors->over_under_cnt;
142 uint16_t i2c1_pec_recep_cnt = softi2c1.errors->pec_recep_cnt;
143 uint16_t i2c1_timeout_tlow_cnt = softi2c1.errors->timeout_tlow_cnt;
144 uint16_t i2c1_smbus_alert_cnt = softi2c1.errors->smbus_alert_cnt;
145 uint16_t i2c1_unexpected_event_cnt = softi2c1.errors->unexpected_event_cnt;
146 uint32_t i2c1_last_unexpected_event = softi2c1.errors->last_unexpected_event;
147 uint8_t _bus1 = 11;
160 &_bus1);
161}
162#endif
163#endif /* USE_SOFTI2C1 */
164
165
167#if defined(CHIBIOS_MCU_ARCH_H) || defined(STM32_MCU_ARCH_H)
168 /* Arch's with input_pullup */
169 gpio_setup_input_pullup(port, pin);
170#else
171 /* Arch's without input_pullup */
172 // Gpio_set might enable pullup on some architectures (e.g. arduino), not sure
173 // if it works here. If not, an external pull-up resistor is required on the
174 // I2C lines.
175 gpio_setup_input(port, pin);
176 gpio_set(port, pin);
177#endif /* arch with/without input_pullup */
178}
179
180static bool softi2c_gpio_read(gpio_port_t port, uint16_t pin) {
181 softi2c_gpio_highz(port, pin);
182 return gpio_get(port, pin);
183}
184
186 gpio_setup_output(port, pin);
187 gpio_clear(port, pin);
188}
189
190static void softi2c_setup_gpio(
193
204
205
206#if USE_SOFTI2C0
208
209void softi2c0_hw_init(void) {
210 softi2c0.idle = softi2c_idle;
211 softi2c0.submit = softi2c_submit;
212 softi2c0.setbitrate = softi2c_setbitrate;
213 softi2c0.spin = softi2c_spin;
214 softi2c0.reg_addr = (void *) &softi2c0_device;
215 softi2c0.errors = &softi2c0_errors;
217
218 softi2c0_device.periph = &softi2c0;
223
224 /* Set up GPIO */
228}
229#endif /* USE_SOFTI2C0 */
230
231#if USE_SOFTI2C1
233
234void softi2c1_hw_init(void) {
235 softi2c1.idle = softi2c_idle;
236 softi2c1.submit = softi2c_submit;
237 softi2c1.setbitrate = softi2c_setbitrate;
238 softi2c1.spin = softi2c_spin;
239 softi2c1.reg_addr = (void *) &softi2c1_device;
240 softi2c1.errors = &softi2c1_errors;
242
243 softi2c1_device.periph = &softi2c1;
248
249 /* Set up GPIO */
253}
254#endif /* USE_SOFTI2C1 */
255
256
257/*
258 * I2C implementation
259 */
260// Some notes about timing:
261// The I2C standard lists timing requirements in the order of microseconds. This
262// is difficult to explicitly implement for two reasons:
263// - The event loop spins at a ~20 us period.
264// - The sys time clock has a resolution of ~200 us. (Can be set higher, but
265// can cause lockups when set to ~2us or lower.)
266// This module handles timing by returning to the event loop at every pause.
267// The event loop runs slow enough to satisfy all I2C standard mode minimum
268// timings. Because the event loop takes longer than the minimum timing, the
269// maximum bitrate is reduced. However, *software*-i2c should not be used for
270// high-bitrate applications anyway.
271// (Experimental code where usleep was used for in-bit timing had only little
272// performance benefit (~20kHz vs ~15kHz). Because sleeping in the event loop
273// can have other negative consequences, this option was removed.)
274// Pauses *between* bits also use the time between event calls as a delay. As a
275// result, the bitrate is an integer fraction of the event rate and cannot be
276// set exactly. The bitrate can be coarsely adjusted per softi2c device by
277// setting SOFTI2CX_DIVIDER.
278
279
280// Bit read/write functions
281// Should be called continuously from event function.
282// Return true upon completion.
283// The bit functions start by setting SCL low and end at the last transition
284// before SCL is set low again. The time between event calls is used to space
285// this last transition and the new SCL low edge, thereby setting the bus
286// frequency.
287
288static bool softi2c_write_start(struct softi2c_device *d) {
290 return true; // > T_HD_STA_MIN
291}
292
293// Note: write_bit may also be used to write the ACK bit (T_VD_ACK == T_VD_DAT)
294static bool softi2c_write_bit(struct softi2c_device *d, bool bit) {
295 switch (d->bit_state) {
296 case 0:
297 // Start of bit
299 d->bit_state++;
300 return false;
301 case 1:
302 // After SCL fall time and data hold time
303 if (bit) {
305 } else {
307 }
308 d->bit_state++;
309 return false;
310 case 2:
311 // After SDA rise(/fall) and data set-up time
313 d->bit_state++;
314 /* Falls through. */
315 case 3:
316 if (!gpio_get(d->scl_port, d->scl_pin)) return false;
317 // After SCL rise time and confirmed high (clock stretching)
318 d->bit_state = 0;
319 return true; // > T_HIGH_MIN
320 default: return false;
321 }
322}
323
324// Note: read_bit may also be used to read the ACK bit (T_VD_ACK == T_VD_DAT)
325static bool softi2c_read_bit(struct softi2c_device *d, bool *bit) {
326 switch (d->bit_state) {
327 case 0:
328 // Start of bit
330 d->bit_state++;
331 return false;
332 case 1:
333 // After SCL fall time and data hold time
334 softi2c_gpio_highz(d->sda_port, d->sda_pin); // SDA may be driven low by slave.
335 // After SCL(!) fall time and minimum low time (== T_HD_DAT_MIN)
337 d->bit_state++;
338 /* Falls through. */
339 case 2:
340 if (!gpio_get(d->scl_port, d->scl_pin)) return false;
341 // After SCL rise time and confirmed high (clock stretching)
343 d->bit_state = 0;
344 return true; // > T_HIGH_MIN
345 default: return false;
346 }
347}
348
349static bool softi2c_write_restart(struct softi2c_device *d) {
350 switch (d->bit_state) {
351 case 0:
352 // Start of bit
354 d->bit_state++;
355 return false;
356 case 1:
357 // After SCL fall time and data hold time
359 d->bit_state++;
360 return false;
361 case 2:
362 // After SDA rise time and data set-up time
364 d->bit_state++;
365 /* Falls through. */
366 case 3:
367 if (!gpio_get(d->scl_port, d->scl_pin)) return false;
368 // After SCL rise time and confirmed high (clock stretching)
369 d->bit_state++;
370 return false;
371 case 4:
372 // After restart set-up time
374 d->bit_state = 0;
375 return true; // > T_HD_STA_MIN
376 default: return false;
377 }
378}
379
380static bool softi2c_write_stop(struct softi2c_device *d) {
381 switch (d->bit_state) {
382 case 0:
383 // Start of bit
385 d->bit_state++;
386 return false;
387 case 1:
388 // After SCL fall time and data hold time
390 d->bit_state++;
391 return false;
392 case 2:
393 // After SDA fall time and data set-up time
395 d->bit_state++;
396 /* Falls through. */
397 case 3:
398 if (!gpio_get(d->scl_port, d->scl_pin)) return false;
399 // After SCL rise time and confirmed high (clock stretching)
400 d->bit_state++;
401 return false;
402 case 4:
403 // After stop set-up time
405 d->bit_state = 0;
406 return true; // > T_BUF_MIN
407 default: return false;
408 }
409}
410
411// Byte read/write functions
412// Should be called continuously from event function.
413// Return true upon completion.
414
415// write_byte:
416// starts with SCL <= low for first bit (start bit is not included!)
417// ends at SCL allowed low
418static bool softi2c_write_byte(struct softi2c_device *d, uint8_t byte, bool *ack) {
419 bool bit;
420 switch (d->byte_state) {
421 case 0:
422 case 1:
423 case 2:
424 case 3:
425 case 4:
426 case 5:
427 case 6:
428 case 7:
429 // Write bit
430 bit = byte & (0x80 >> d->byte_state); // MSB first
431 if (!softi2c_write_bit(d, bit)) return false; // Write bit in progress
432 d->byte_state++;
433 return false;
434 case 8:
435 // Read ACK
436 if (!softi2c_read_bit(d, ack)) return false; // Read bit in progress
437 *ack = !*ack; // Inverted, low = acknowledge
438 d->byte_state = 0;
439 return true;
440 default: return false;
441 }
442}
443
444// read_byte:
445// starts with SCL <= low for first bit (start bit is not included!)
446// ends at SCL allowed low
447// Note: ack should be false when reading last byte (UM10204 3.1.10)
448static bool softi2c_read_byte(struct softi2c_device *d, uint8_t *byte, bool ack) {
449 bool bit;
450 switch (d->byte_state) {
451 case 0:
452 case 1:
453 case 2:
454 case 3:
455 case 4:
456 case 5:
457 case 6:
458 case 7:
459 // Read bit
460 if (!softi2c_read_bit(d, &bit)) return false; // Read bit in progress
461 if (bit) {
462 *byte |= (0x80 >> d->byte_state); // MSB first
463 } else {
464 *byte &= ~(0x80 >> d->byte_state); // MSB first
465 }
466 d->byte_state++;
467 return false;
468 case 8:
469 // Write ACK
470 // Note: inverted logic, low = acknowledge.
471 if (!softi2c_write_bit(d, !ack)) return false; // Write bit in progress
472 d->byte_state = 0;
473 return true;
474 default: return false;
475 }
476}
477
478// Transaction handling
479// Should be called continously from event function.
480// Returns true upon completion.
481#pragma GCC diagnostic push
482#pragma GCC diagnostic ignored "-Wcast-qual"
485 bool ack;
486 switch (d->periph->status) {
487 case I2CIdle:
488 // Start of transaction
489 t->status = I2CTransRunning;
491 d->periph->idx_buf = 0;
492 return false;
493
495 // Send start bit
496 if (!softi2c_write_start(d)) return false;
497 // Start bit sent
498 if (t->type == I2CTransRx) {
500 } else {
502 }
503 return false;
504
505 case I2CAddrWrSent:
506 // Send write address
507 if (!softi2c_write_byte(d, t->slave_addr, &ack)) return false;
508 // Write address sent
509 if (!ack) {
511 d->periph->status = I2CFailed;
512 return false;
513 }
515 return false;
516
517 case I2CSendingByte:
518 // Check remaining bytes
519 if (d->periph->idx_buf >= t->len_w) {
520 d->periph->idx_buf = 0;
521 if (t->type == I2CTransTxRx) {
523 } else {
525 }
526 return false;
527 }
528 // Send byte
529 if (!softi2c_write_byte(d, t->buf[d->periph->idx_buf], &ack)) return false;
530 // Byte sent
531 if (!ack) {
533 d->periph->status = I2CFailed;
534 return true;
535 }
536 d->periph->idx_buf++;
537 return false;
538
540 // Send restart bit
541 if (!softi2c_write_restart(d)) return false;
542 // Restart bit sent
544 return false;
545
546 case I2CAddrRdSent:
547 // Send read address
548 byte = t->slave_addr | 0x01;
549 if (!softi2c_write_byte(d, byte, &ack)) return false;
550 // Read address sent
551 if (!ack) {
553 d->periph->status = I2CFailed;
554 return true;
555 }
557 return false;
558
559 case I2CReadingByte:
560 // Check remaining bytes
561 if (d->periph->idx_buf >= t->len_r - 1) {
563 return false;
564 }
565 // Read byte
566 if (!softi2c_read_byte(d, (uint8_t *) &(t->buf[d->periph->idx_buf]), true)) return false;
567 // Byte read
568 d->periph->idx_buf++;
569 return false;
570
572 // Check remaining bytes
573 if (d->periph->idx_buf >= t->len_r) {
574 d->periph->idx_buf = 0;
576 return false;
577 }
578 // Read last byte (no ACK!)
579 if (!softi2c_read_byte(d, (uint8_t *) &(t->buf[d->periph->idx_buf]), false)) return false;
580 // Byte read
581 d->periph->idx_buf++;
582 return false;
583
584 case I2CStopRequested:
585 // Send stop bit
586 if (!softi2c_write_stop(d)) return false;
587 // Stop bit sent
588 t->status = I2CTransSuccess;
589 d->periph->status = I2CIdle;
590 return true;
591
592 default:
593 case I2CFailed:
594 // Something went wrong
595 // Send stop bit
596 if (!softi2c_write_stop(d)) return false;
597 // Stop bit sent
598 t->status = I2CTransFailed;
599 d->periph->status = I2CIdle;
600 return true;
601 }
602}
603#pragma GCC diagnostic pop
604
605// Per-device event function
606static void softi2c_device_event(struct softi2c_device *d) __attribute__((unused));
607
608static void softi2c_device_event(struct softi2c_device *d) {
609 struct i2c_periph *p = d->periph;
610 if (p->trans_insert_idx != p->trans_extract_idx) {
611 // Transaction(s) in queue
612 struct i2c_transaction *t = p->trans[p->trans_extract_idx];
614 // Transaction finished
615 p->trans_extract_idx = (p->trans_extract_idx + 1) % I2C_TRANSACTION_QUEUE_LEN;
616 }
617 }
618}
619
620
621/*
622 * Paparazzi functions
623 */
624void softi2c_event(void) {
625#if USE_SOFTI2C0
626 static int softi2c0_cnt = 1;
629 softi2c0_cnt = 1;
630 } else {
631 softi2c0_cnt++;
632 }
633#endif
634#if USE_SOFTI2C1
635 static int softi2c1_cnt = 1;
638 softi2c1_cnt = 1;
639 } else {
640 softi2c1_cnt++;
641 }
642#endif
643}
644
645static void softi2c_spin(struct i2c_periph *p) {
646 softi2c_device_event((struct softi2c_device *) p->reg_addr);
647// sys_time_usleep(5); // For I2C timing. // TvD 2020-08-18: Hangs? Interrupt issue when called from SPI?
648}
649
650static bool softi2c_idle(struct i2c_periph *p) {
651 return (p->status == I2CIdle) && (p->trans_insert_idx == p->trans_extract_idx);
652}
653
654static bool softi2c_submit(struct i2c_periph *p, struct i2c_transaction *t) {
655 uint8_t next_idx = (p->trans_insert_idx + 1) % I2C_TRANSACTION_QUEUE_LEN;
656 if (next_idx == p->trans_extract_idx) {
657 // queue full
658 p->errors->queue_full_cnt++;
659 t->status = I2CTransFailed;
660 return false;
661 }
662 t->status = I2CTransPending;
663 /* put transaction in queue */
664 p->trans[p->trans_insert_idx] = t;
665 p->trans_insert_idx = next_idx;
666 return true;
667}
668
669static void softi2c_setbitrate(struct i2c_periph *p __attribute__((unused)), int bitrate __attribute__((unused))) {
670 /* Do nothing */
671}
void gpio_setup_input_pullup(ioportid_t port, uint16_t gpios)
Setup one or more pins of the given GPIO port as inputs with pull up resistor enabled.
Definition gpio_arch.c:47
void gpio_setup_output(ioportid_t port, uint16_t gpios)
Setup one or more pins of the given GPIO port as outputs.
Definition gpio_arch.c:33
void gpio_setup_input(ioportid_t port, uint16_t gpios)
Setup one or more pins of the given GPIO port as inputs.
Definition gpio_arch.c:40
static void gpio_set(ioportid_t port, uint16_t pin)
Set a gpio output to high level.
Definition gpio_arch.h:104
static void gpio_clear(ioportid_t port, uint16_t pin)
Clear a gpio output to low level.
Definition gpio_arch.h:114
ioportid_t gpio_port_t
Abstract gpio port type for hardware independent part.
Definition gpio_arch.h:39
static uint8_t gpio_get(ioportid_t port, uint16_t pin)
Get level of a gpio.
Definition gpio_arch.h:94
Some architecture independent helper functions for GPIOs.
struct i2c_errors * errors
Definition i2c.h:159
volatile uint16_t ack_fail_cnt
Definition i2c.h:168
volatile uint8_t idx_buf
Definition i2c.h:156
enum I2CStatus status
Definition i2c.h:155
#define ZEROS_ERR_COUNTER(_i2c_err)
Definition i2c.h:181
#define I2C_TRANSACTION_QUEUE_LEN
I2C transaction queue length.
Definition i2c.h:133
void i2c_init(struct i2c_periph *p)
Initialize I2C peripheral.
Definition i2c.c:188
@ I2CStopRequested
Definition i2c.h:74
@ I2CAddrRdSent
Definition i2c.h:69
@ I2CFailed
Definition i2c.h:77
@ I2CAddrWrSent
Definition i2c.h:68
@ I2CIdle
Definition i2c.h:66
@ I2CStartRequested
Definition i2c.h:67
@ I2CReadingByte
Definition i2c.h:72
@ I2CSendingByte
Definition i2c.h:70
@ I2CReadingLastByte
Definition i2c.h:73
@ I2CRestartRequested
Definition i2c.h:75
@ I2CTransRunning
transaction is currently ongoing
Definition i2c.h:56
@ I2CTransSuccess
transaction successfully finished by I2C driver
Definition i2c.h:57
@ I2CTransFailed
transaction failed
Definition i2c.h:58
@ I2CTransPending
transaction is pending in queue
Definition i2c.h:55
@ I2CTransRx
receive only transaction
Definition i2c.h:48
@ I2CTransTxRx
transmit and receive transaction
Definition i2c.h:49
I2C errors counter.
Definition i2c.h:165
I2C transaction structure.
Definition i2c.h:93
static float p[2][2]
uint16_t foo
Definition main_demo5.c:58
#define byte
void softi2c_event(void)
Definition softi2c.c:624
#define SOFTI2C1_DIVIDER
Definition softi2c.c:48
static bool softi2c_write_restart(struct softi2c_device *d)
Definition softi2c.c:349
static void softi2c_device_event(struct softi2c_device *d)
Definition softi2c.c:608
#define SOFTI2C0_DIVIDER
Definition softi2c.c:45
static bool softi2c_submit(struct i2c_periph *periph, struct i2c_transaction *t)
Definition softi2c.c:654
static bool softi2c_idle(struct i2c_periph *periph)
Definition softi2c.c:650
uint8_t byte_state
Definition softi2c.c:61
gpio_port_t scl_port
Definition softi2c.c:56
static bool softi2c_read_bit(struct softi2c_device *d, bool *bit)
Definition softi2c.c:325
static void softi2c_setbitrate(struct i2c_periph *periph, int bitrate)
Definition softi2c.c:669
static void softi2c_gpio_drive_low(gpio_port_t port, uint16_t pin)
Definition softi2c.c:185
static void softi2c_gpio_highz(gpio_port_t port, uint16_t pin)
Definition softi2c.c:166
struct i2c_periph * periph
Definition softi2c.c:53
static bool softi2c_gpio_read(gpio_port_t port, uint16_t pin)
Definition softi2c.c:180
static bool softi2c_write_byte(struct softi2c_device *d, uint8_t byte, bool *ack)
Definition softi2c.c:418
static void softi2c_setup_gpio(gpio_port_t sda_port, uint16_t sda_pin, gpio_port_t scl_port, uint16_t scl_pin)
Definition softi2c.c:194
static bool softi2c_write_bit(struct softi2c_device *d, bool bit)
Definition softi2c.c:294
uint16_t scl_pin
Definition softi2c.c:57
uint8_t bit_state
Definition softi2c.c:59
uint16_t sda_pin
Definition softi2c.c:55
static bool softi2c_process_transaction(struct softi2c_device *d, struct i2c_transaction *t)
Definition softi2c.c:483
gpio_port_t sda_port
Definition softi2c.c:54
static bool softi2c_write_start(struct softi2c_device *d)
Definition softi2c.c:288
static bool softi2c_write_stop(struct softi2c_device *d)
Definition softi2c.c:380
static void softi2c_spin(struct i2c_periph *p)
Definition softi2c.c:645
static bool softi2c_read_byte(struct softi2c_device *d, uint8_t *byte, bool ack)
Definition softi2c.c:448
Platform-independent software I2C implementation.
void gpio_enable_clock(uint32_t port)
Enable the relevant clock.
Definition gpio_arch.c:34
static const struct usb_device_descriptor dev
Definition usb_ser_hw.c:74
Architecture independent timing functions.
Periodic telemetry system header (includes downlink utility and generated code).
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.