Squashed 'third_party/pico-sdk/' content from commit 2062372d2
Change-Id: Ic20f199d3ed0ea8d3a6a1bbf513f875ec7500cc6
git-subtree-dir: third_party/pico-sdk
git-subtree-split: 2062372d203b372849d573f252cf7c6dc2800c0a
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/src/rp2_common/hardware_i2c/CMakeLists.txt b/src/rp2_common/hardware_i2c/CMakeLists.txt
new file mode 100644
index 0000000..aba48dd
--- /dev/null
+++ b/src/rp2_common/hardware_i2c/CMakeLists.txt
@@ -0,0 +1 @@
+pico_simple_hardware_target(i2c)
diff --git a/src/rp2_common/hardware_i2c/i2c.c b/src/rp2_common/hardware_i2c/i2c.c
new file mode 100644
index 0000000..95bcfea
--- /dev/null
+++ b/src/rp2_common/hardware_i2c/i2c.c
@@ -0,0 +1,337 @@
+/*
+ * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include "hardware/i2c.h"
+#include "hardware/resets.h"
+#include "hardware/clocks.h"
+#include "pico/timeout_helper.h"
+
+check_hw_layout(i2c_hw_t, enable, I2C_IC_ENABLE_OFFSET);
+check_hw_layout(i2c_hw_t, clr_restart_det, I2C_IC_CLR_RESTART_DET_OFFSET);
+
+i2c_inst_t i2c0_inst = {i2c0_hw, false};
+i2c_inst_t i2c1_inst = {i2c1_hw, false};
+
+static inline void i2c_reset(i2c_inst_t *i2c) {
+ invalid_params_if(I2C, i2c != i2c0 && i2c != i2c1);
+ reset_block(i2c == i2c0 ? RESETS_RESET_I2C0_BITS : RESETS_RESET_I2C1_BITS);
+}
+
+static inline void i2c_unreset(i2c_inst_t *i2c) {
+ invalid_params_if(I2C, i2c != i2c0 && i2c != i2c1);
+ unreset_block_wait(i2c == i2c0 ? RESETS_RESET_I2C0_BITS : RESETS_RESET_I2C1_BITS);
+}
+
+// Addresses of the form 000 0xxx or 111 1xxx are reserved. No slave should
+// have these addresses.
+static inline bool i2c_reserved_addr(uint8_t addr) {
+ return (addr & 0x78) == 0 || (addr & 0x78) == 0x78;
+}
+
+uint i2c_init(i2c_inst_t *i2c, uint baudrate) {
+ i2c_reset(i2c);
+ i2c_unreset(i2c);
+ i2c->restart_on_next = false;
+
+ i2c->hw->enable = 0;
+
+ // Configure as a fast-mode master with RepStart support, 7-bit addresses
+ i2c->hw->con =
+ I2C_IC_CON_SPEED_VALUE_FAST << I2C_IC_CON_SPEED_LSB |
+ I2C_IC_CON_MASTER_MODE_BITS |
+ I2C_IC_CON_IC_SLAVE_DISABLE_BITS |
+ I2C_IC_CON_IC_RESTART_EN_BITS |
+ I2C_IC_CON_TX_EMPTY_CTRL_BITS;
+
+ // Set FIFO watermarks to 1 to make things simpler. This is encoded by a register value of 0.
+ i2c->hw->tx_tl = 0;
+ i2c->hw->rx_tl = 0;
+
+ // Always enable the DREQ signalling -- harmless if DMA isn't listening
+ i2c->hw->dma_cr = I2C_IC_DMA_CR_TDMAE_BITS | I2C_IC_DMA_CR_RDMAE_BITS;
+
+ // Re-sets i2c->hw->enable upon returning:
+ return i2c_set_baudrate(i2c, baudrate);
+}
+
+void i2c_deinit(i2c_inst_t *i2c) {
+ i2c_reset(i2c);
+}
+
+uint i2c_set_baudrate(i2c_inst_t *i2c, uint baudrate) {
+ invalid_params_if(I2C, baudrate == 0);
+ // I2C is synchronous design that runs from clk_sys
+ uint freq_in = clock_get_hz(clk_sys);
+
+ // TODO there are some subtleties to I2C timing which we are completely ignoring here
+ uint period = (freq_in + baudrate / 2) / baudrate;
+ uint lcnt = period * 3 / 5; // oof this one hurts
+ uint hcnt = period - lcnt;
+ // Check for out-of-range divisors:
+ invalid_params_if(I2C, hcnt > I2C_IC_FS_SCL_HCNT_IC_FS_SCL_HCNT_BITS);
+ invalid_params_if(I2C, lcnt > I2C_IC_FS_SCL_LCNT_IC_FS_SCL_LCNT_BITS);
+ invalid_params_if(I2C, hcnt < 8);
+ invalid_params_if(I2C, lcnt < 8);
+
+ // Per I2C-bus specification a device in standard or fast mode must
+ // internally provide a hold time of at least 300ns for the SDA signal to
+ // bridge the undefined region of the falling edge of SCL. A smaller hold
+ // time of 120ns is used for fast mode plus.
+ uint sda_tx_hold_count;
+ if (baudrate < 1000000) {
+ // sda_tx_hold_count = freq_in [cycles/s] * 300ns * (1s / 1e9ns)
+ // Reduce 300/1e9 to 3/1e7 to avoid numbers that don't fit in uint.
+ // Add 1 to avoid division truncation.
+ sda_tx_hold_count = ((freq_in * 3) / 10000000) + 1;
+ } else {
+ // sda_tx_hold_count = freq_in [cycles/s] * 120ns * (1s / 1e9ns)
+ // Reduce 120/1e9 to 3/25e6 to avoid numbers that don't fit in uint.
+ // Add 1 to avoid division truncation.
+ sda_tx_hold_count = ((freq_in * 3) / 25000000) + 1;
+ }
+ assert(sda_tx_hold_count <= lcnt - 2);
+
+ i2c->hw->enable = 0;
+ // Always use "fast" mode (<= 400 kHz, works fine for standard mode too)
+ hw_write_masked(&i2c->hw->con,
+ I2C_IC_CON_SPEED_VALUE_FAST << I2C_IC_CON_SPEED_LSB,
+ I2C_IC_CON_SPEED_BITS
+ );
+ i2c->hw->fs_scl_hcnt = hcnt;
+ i2c->hw->fs_scl_lcnt = lcnt;
+ i2c->hw->fs_spklen = lcnt < 16 ? 1 : lcnt / 16;
+ hw_write_masked(&i2c->hw->sda_hold,
+ sda_tx_hold_count << I2C_IC_SDA_HOLD_IC_SDA_TX_HOLD_LSB,
+ I2C_IC_SDA_HOLD_IC_SDA_TX_HOLD_BITS);
+
+ i2c->hw->enable = 1;
+ return freq_in / period;
+}
+
+void i2c_set_slave_mode(i2c_inst_t *i2c, bool slave, uint8_t addr) {
+ invalid_params_if(I2C, addr >= 0x80); // 7-bit addresses
+ invalid_params_if(I2C, i2c_reserved_addr(addr));
+ i2c->hw->enable = 0;
+ uint32_t ctrl_set_if_master = I2C_IC_CON_MASTER_MODE_BITS | I2C_IC_CON_IC_SLAVE_DISABLE_BITS;
+ uint32_t ctrl_set_if_slave = I2C_IC_CON_RX_FIFO_FULL_HLD_CTRL_BITS;
+ if (slave) {
+ hw_write_masked(&i2c->hw->con,
+ ctrl_set_if_slave,
+ ctrl_set_if_master | ctrl_set_if_slave
+ );
+ i2c->hw->sar = addr;
+ } else {
+ hw_write_masked(&i2c->hw->con,
+ ctrl_set_if_master,
+ ctrl_set_if_master | ctrl_set_if_slave
+ );
+ }
+ i2c->hw->enable = 1;
+}
+
+static int i2c_write_blocking_internal(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop,
+ check_timeout_fn timeout_check, struct timeout_state *ts) {
+ invalid_params_if(I2C, addr >= 0x80); // 7-bit addresses
+ invalid_params_if(I2C, i2c_reserved_addr(addr));
+ // Synopsys hw accepts start/stop flags alongside data items in the same
+ // FIFO word, so no 0 byte transfers.
+ invalid_params_if(I2C, len == 0);
+ invalid_params_if(I2C, ((int)len) < 0);
+
+ i2c->hw->enable = 0;
+ i2c->hw->tar = addr;
+ i2c->hw->enable = 1;
+
+ bool abort = false;
+ bool timeout = false;
+
+ uint32_t abort_reason = 0;
+ int byte_ctr;
+
+ int ilen = (int)len;
+ for (byte_ctr = 0; byte_ctr < ilen; ++byte_ctr) {
+ bool first = byte_ctr == 0;
+ bool last = byte_ctr == ilen - 1;
+
+ i2c->hw->data_cmd =
+ bool_to_bit(first && i2c->restart_on_next) << I2C_IC_DATA_CMD_RESTART_LSB |
+ bool_to_bit(last && !nostop) << I2C_IC_DATA_CMD_STOP_LSB |
+ *src++;
+
+ // Wait until the transmission of the address/data from the internal
+ // shift register has completed. For this to function correctly, the
+ // TX_EMPTY_CTRL flag in IC_CON must be set. The TX_EMPTY_CTRL flag
+ // was set in i2c_init.
+ do {
+ if (timeout_check) {
+ timeout = timeout_check(ts);
+ abort |= timeout;
+ }
+ tight_loop_contents();
+ } while (!timeout && !(i2c->hw->raw_intr_stat & I2C_IC_RAW_INTR_STAT_TX_EMPTY_BITS));
+
+ // If there was a timeout, don't attempt to do anything else.
+ if (!timeout) {
+ abort_reason = i2c->hw->tx_abrt_source;
+ if (abort_reason) {
+ // Note clearing the abort flag also clears the reason, and
+ // this instance of flag is clear-on-read! Note also the
+ // IC_CLR_TX_ABRT register always reads as 0.
+ i2c->hw->clr_tx_abrt;
+ abort = true;
+ }
+
+ if (abort || (last && !nostop)) {
+ // If the transaction was aborted or if it completed
+ // successfully wait until the STOP condition has occured.
+
+ // TODO Could there be an abort while waiting for the STOP
+ // condition here? If so, additional code would be needed here
+ // to take care of the abort.
+ do {
+ if (timeout_check) {
+ timeout = timeout_check(ts);
+ abort |= timeout;
+ }
+ tight_loop_contents();
+ } while (!timeout && !(i2c->hw->raw_intr_stat & I2C_IC_RAW_INTR_STAT_STOP_DET_BITS));
+
+ // If there was a timeout, don't attempt to do anything else.
+ if (!timeout) {
+ i2c->hw->clr_stop_det;
+ }
+ }
+ }
+
+ // Note the hardware issues a STOP automatically on an abort condition.
+ // Note also the hardware clears RX FIFO as well as TX on abort,
+ // because we set hwparam IC_AVOID_RX_FIFO_FLUSH_ON_TX_ABRT to 0.
+ if (abort)
+ break;
+ }
+
+ int rval;
+
+ // A lot of things could have just happened due to the ingenious and
+ // creative design of I2C. Try to figure things out.
+ if (abort) {
+ if (timeout)
+ rval = PICO_ERROR_TIMEOUT;
+ else if (!abort_reason || abort_reason & I2C_IC_TX_ABRT_SOURCE_ABRT_7B_ADDR_NOACK_BITS) {
+ // No reported errors - seems to happen if there is nothing connected to the bus.
+ // Address byte not acknowledged
+ rval = PICO_ERROR_GENERIC;
+ } else if (abort_reason & I2C_IC_TX_ABRT_SOURCE_ABRT_TXDATA_NOACK_BITS) {
+ // Address acknowledged, some data not acknowledged
+ rval = byte_ctr;
+ } else {
+ //panic("Unknown abort from I2C instance @%08x: %08x\n", (uint32_t) i2c->hw, abort_reason);
+ rval = PICO_ERROR_GENERIC;
+ }
+ } else {
+ rval = byte_ctr;
+ }
+
+ // nostop means we are now at the end of a *message* but not the end of a *transfer*
+ i2c->restart_on_next = nostop;
+ return rval;
+}
+
+int i2c_write_blocking(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop) {
+ return i2c_write_blocking_internal(i2c, addr, src, len, nostop, NULL, NULL);
+}
+
+int i2c_write_blocking_until(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop,
+ absolute_time_t until) {
+ timeout_state_t ts;
+ return i2c_write_blocking_internal(i2c, addr, src, len, nostop, init_single_timeout_until(&ts, until), &ts);
+}
+
+int i2c_write_timeout_per_char_us(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop,
+ uint timeout_per_char_us) {
+ timeout_state_t ts;
+ return i2c_write_blocking_internal(i2c, addr, src, len, nostop,
+ init_per_iteration_timeout_us(&ts, timeout_per_char_us), &ts);
+}
+
+static int i2c_read_blocking_internal(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop,
+ check_timeout_fn timeout_check, timeout_state_t *ts) {
+ invalid_params_if(I2C, addr >= 0x80); // 7-bit addresses
+ invalid_params_if(I2C, i2c_reserved_addr(addr));
+ invalid_params_if(I2C, len == 0);
+ invalid_params_if(I2C, ((int)len) < 0);
+
+ i2c->hw->enable = 0;
+ i2c->hw->tar = addr;
+ i2c->hw->enable = 1;
+
+ bool abort = false;
+ bool timeout = false;
+ uint32_t abort_reason;
+ int byte_ctr;
+ int ilen = (int)len;
+ for (byte_ctr = 0; byte_ctr < ilen; ++byte_ctr) {
+ bool first = byte_ctr == 0;
+ bool last = byte_ctr == ilen - 1;
+ while (!i2c_get_write_available(i2c))
+ tight_loop_contents();
+
+ i2c->hw->data_cmd =
+ bool_to_bit(first && i2c->restart_on_next) << I2C_IC_DATA_CMD_RESTART_LSB |
+ bool_to_bit(last && !nostop) << I2C_IC_DATA_CMD_STOP_LSB |
+ I2C_IC_DATA_CMD_CMD_BITS; // -> 1 for read
+
+ do {
+ abort_reason = i2c->hw->tx_abrt_source;
+ abort = (bool) i2c->hw->clr_tx_abrt;
+ if (timeout_check) {
+ timeout = timeout_check(ts);
+ abort |= timeout;
+ }
+ } while (!abort && !i2c_get_read_available(i2c));
+
+ if (abort)
+ break;
+
+ *dst++ = (uint8_t) i2c->hw->data_cmd;
+ }
+
+ int rval;
+
+ if (abort) {
+ if (timeout)
+ rval = PICO_ERROR_TIMEOUT;
+ else if (!abort_reason || abort_reason & I2C_IC_TX_ABRT_SOURCE_ABRT_7B_ADDR_NOACK_BITS) {
+ // No reported errors - seems to happen if there is nothing connected to the bus.
+ // Address byte not acknowledged
+ rval = PICO_ERROR_GENERIC;
+ } else {
+// panic("Unknown abort from I2C instance @%08x: %08x\n", (uint32_t) i2c->hw, abort_reason);
+ rval = PICO_ERROR_GENERIC;
+ }
+ } else {
+ rval = byte_ctr;
+ }
+
+ i2c->restart_on_next = nostop;
+ return rval;
+}
+
+int i2c_read_blocking(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop) {
+ return i2c_read_blocking_internal(i2c, addr, dst, len, nostop, NULL, NULL);
+}
+
+int i2c_read_blocking_until(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop, absolute_time_t until) {
+ timeout_state_t ts;
+ return i2c_read_blocking_internal(i2c, addr, dst, len, nostop, init_single_timeout_until(&ts, until), &ts);
+}
+
+int i2c_read_timeout_per_char_us(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop,
+ uint timeout_per_char_us) {
+ timeout_state_t ts;
+ return i2c_read_blocking_internal(i2c, addr, dst, len, nostop,
+ init_per_iteration_timeout_us(&ts, timeout_per_char_us), &ts);
+}
diff --git a/src/rp2_common/hardware_i2c/include/hardware/i2c.h b/src/rp2_common/hardware_i2c/include/hardware/i2c.h
new file mode 100644
index 0000000..23ff8f1
--- /dev/null
+++ b/src/rp2_common/hardware_i2c/include/hardware/i2c.h
@@ -0,0 +1,332 @@
+/*
+ * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef _HARDWARE_I2C_H
+#define _HARDWARE_I2C_H
+
+#include "pico.h"
+#include "pico/time.h"
+#include "hardware/structs/i2c.h"
+#include "hardware/regs/dreq.h"
+
+// PICO_CONFIG: PARAM_ASSERTIONS_ENABLED_I2C, Enable/disable assertions in the I2C module, type=bool, default=0, group=hardware_i2c
+#ifndef PARAM_ASSERTIONS_ENABLED_I2C
+#define PARAM_ASSERTIONS_ENABLED_I2C 0
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** \file hardware/i2c.h
+ * \defgroup hardware_i2c hardware_i2c
+ *
+ * I2C Controller API
+ *
+ * The I2C bus is a two-wire serial interface, consisting of a serial data line SDA and a serial clock SCL. These wires carry
+ * information between the devices connected to the bus. Each device is recognized by a unique 7-bit address and can operate as
+ * either a “transmitter” or “receiver”, depending on the function of the device. Devices can also be considered as masters or
+ * slaves when performing data transfers. A master is a device that initiates a data transfer on the bus and generates the
+ * clock signals to permit that transfer. The first byte in the data transfer always contains the 7-bit address and
+ * a read/write bit in the LSB position. This API takes care of toggling the read/write bit. After this, any device addressed
+ * is considered a slave.
+ *
+ * This API allows the controller to be set up as a master or a slave using the \ref i2c_set_slave_mode function.
+ *
+ * The external pins of each controller are connected to GPIO pins as defined in the GPIO muxing table in the datasheet. The muxing options
+ * give some IO flexibility, but each controller external pin should be connected to only one GPIO.
+ *
+ * Note that the controller does NOT support High speed mode or Ultra-fast speed mode, the fastest operation being fast mode plus
+ * at up to 1000Kb/s.
+ *
+ * See the datasheet for more information on the I2C controller and its usage.
+ *
+ * \subsection i2c_example Example
+ * \addtogroup hardware_i2c
+ * \include bus_scan.c
+ */
+
+typedef struct i2c_inst i2c_inst_t;
+
+// PICO_CONFIG: PICO_DEFAULT_I2C, Define the default I2C for a board, min=0, max=1, group=hardware_i2c
+// PICO_CONFIG: PICO_DEFAULT_I2C_SDA_PIN, Define the default I2C SDA pin, min=0, max=29, group=hardware_i2c
+// PICO_CONFIG: PICO_DEFAULT_I2C_SCL_PIN, Define the default I2C SCL pin, min=0, max=29, group=hardware_i2c
+
+/** The I2C identifiers for use in I2C functions.
+ *
+ * e.g. i2c_init(i2c0, 48000)
+ *
+ * \ingroup hardware_i2c
+ * @{
+ */
+extern i2c_inst_t i2c0_inst;
+extern i2c_inst_t i2c1_inst;
+
+#define i2c0 (&i2c0_inst) ///< Identifier for I2C HW Block 0
+#define i2c1 (&i2c1_inst) ///< Identifier for I2C HW Block 1
+
+#if !defined(PICO_DEFAULT_I2C_INSTANCE) && defined(PICO_DEFAULT_I2C)
+#define PICO_DEFAULT_I2C_INSTANCE (__CONCAT(i2c,PICO_DEFAULT_I2C))
+#endif
+
+#ifdef PICO_DEFAULT_I2C_INSTANCE
+#define i2c_default PICO_DEFAULT_I2C_INSTANCE
+#endif
+
+/** @} */
+
+// ----------------------------------------------------------------------------
+// Setup
+
+/*! \brief Initialise the I2C HW block
+ * \ingroup hardware_i2c
+ *
+ * Put the I2C hardware into a known state, and enable it. Must be called
+ * before other functions. By default, the I2C is configured to operate as a
+ * master.
+ *
+ * The I2C bus frequency is set as close as possible to requested, and
+ * the return actual rate set is returned
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param baudrate Baudrate in Hz (e.g. 100kHz is 100000)
+ * \return Actual set baudrate
+ */
+uint i2c_init(i2c_inst_t *i2c, uint baudrate);
+
+/*! \brief Disable the I2C HW block
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ *
+ * Disable the I2C again if it is no longer used. Must be reinitialised before
+ * being used again.
+ */
+void i2c_deinit(i2c_inst_t *i2c);
+
+/*! \brief Set I2C baudrate
+ * \ingroup hardware_i2c
+ *
+ * Set I2C bus frequency as close as possible to requested, and return actual
+ * rate set.
+ * Baudrate may not be as exactly requested due to clocking limitations.
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param baudrate Baudrate in Hz (e.g. 100kHz is 100000)
+ * \return Actual set baudrate
+ */
+uint i2c_set_baudrate(i2c_inst_t *i2c, uint baudrate);
+
+/*! \brief Set I2C port to slave mode
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param slave true to use slave mode, false to use master mode
+ * \param addr If \p slave is true, set the slave address to this value
+ */
+void i2c_set_slave_mode(i2c_inst_t *i2c, bool slave, uint8_t addr);
+
+// ----------------------------------------------------------------------------
+// Generic input/output
+
+struct i2c_inst {
+ i2c_hw_t *hw;
+ bool restart_on_next;
+};
+
+/*! \brief Convert I2C instance to hardware instance number
+ * \ingroup hardware_i2c
+ *
+ * \param i2c I2C instance
+ * \return Number of I2C, 0 or 1.
+ */
+static inline uint i2c_hw_index(i2c_inst_t *i2c) {
+ invalid_params_if(I2C, i2c != i2c0 && i2c != i2c1);
+ return i2c == i2c1 ? 1 : 0;
+}
+
+static inline i2c_hw_t *i2c_get_hw(i2c_inst_t *i2c) {
+ i2c_hw_index(i2c); // check it is a hw i2c
+ return i2c->hw;
+}
+
+/*! \brief Attempt to write specified number of bytes to address, blocking until the specified absolute time is reached.
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param addr 7-bit address of device to write to
+ * \param src Pointer to data to send
+ * \param len Length of data in bytes to send
+ * \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
+ * and the next transfer will begin with a Restart rather than a Start.
+ * \param until The absolute time that the block will wait until the entire transaction is complete. Note, an individual timeout of
+ * this value divided by the length of data is applied for each byte transfer, so if the first or subsequent
+ * bytes fails to transfer within that sub timeout, the function will return with an error.
+ *
+ * \return Number of bytes written, or PICO_ERROR_GENERIC if address not acknowledged, no device present, or PICO_ERROR_TIMEOUT if a timeout occurred.
+ */
+int i2c_write_blocking_until(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop, absolute_time_t until);
+
+/*! \brief Attempt to read specified number of bytes from address, blocking until the specified absolute time is reached.
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param addr 7-bit address of device to read from
+ * \param dst Pointer to buffer to receive data
+ * \param len Length of data in bytes to receive
+ * \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
+ * and the next transfer will begin with a Restart rather than a Start.
+ * \param until The absolute time that the block will wait until the entire transaction is complete.
+ * \return Number of bytes read, or PICO_ERROR_GENERIC if address not acknowledged, no device present, or PICO_ERROR_TIMEOUT if a timeout occurred.
+ */
+int i2c_read_blocking_until(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop, absolute_time_t until);
+
+/*! \brief Attempt to write specified number of bytes to address, with timeout
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param addr 7-bit address of device to write to
+ * \param src Pointer to data to send
+ * \param len Length of data in bytes to send
+ * \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
+ * and the next transfer will begin with a Restart rather than a Start.
+ * \param timeout_us The time that the function will wait for the entire transaction to complete. Note, an individual timeout of
+ * this value divided by the length of data is applied for each byte transfer, so if the first or subsequent
+ * bytes fails to transfer within that sub timeout, the function will return with an error.
+ *
+ * \return Number of bytes written, or PICO_ERROR_GENERIC if address not acknowledged, no device present, or PICO_ERROR_TIMEOUT if a timeout occurred.
+ */
+static inline int i2c_write_timeout_us(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop, uint timeout_us) {
+ absolute_time_t t = make_timeout_time_us(timeout_us);
+ return i2c_write_blocking_until(i2c, addr, src, len, nostop, t);
+}
+
+int i2c_write_timeout_per_char_us(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop, uint timeout_per_char_us);
+
+/*! \brief Attempt to read specified number of bytes from address, with timeout
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param addr 7-bit address of device to read from
+ * \param dst Pointer to buffer to receive data
+ * \param len Length of data in bytes to receive
+ * \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
+ * and the next transfer will begin with a Restart rather than a Start.
+ * \param timeout_us The time that the function will wait for the entire transaction to complete
+ * \return Number of bytes read, or PICO_ERROR_GENERIC if address not acknowledged, no device present, or PICO_ERROR_TIMEOUT if a timeout occurred.
+ */
+static inline int i2c_read_timeout_us(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop, uint timeout_us) {
+ absolute_time_t t = make_timeout_time_us(timeout_us);
+ return i2c_read_blocking_until(i2c, addr, dst, len, nostop, t);
+}
+
+int i2c_read_timeout_per_char_us(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop, uint timeout_per_char_us);
+
+/*! \brief Attempt to write specified number of bytes to address, blocking
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param addr 7-bit address of device to write to
+ * \param src Pointer to data to send
+ * \param len Length of data in bytes to send
+ * \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
+ * and the next transfer will begin with a Restart rather than a Start.
+ * \return Number of bytes written, or PICO_ERROR_GENERIC if address not acknowledged, no device present.
+ */
+int i2c_write_blocking(i2c_inst_t *i2c, uint8_t addr, const uint8_t *src, size_t len, bool nostop);
+
+/*! \brief Attempt to read specified number of bytes from address, blocking
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param addr 7-bit address of device to read from
+ * \param dst Pointer to buffer to receive data
+ * \param len Length of data in bytes to receive
+ * \param nostop If true, master retains control of the bus at the end of the transfer (no Stop is issued),
+ * and the next transfer will begin with a Restart rather than a Start.
+ * \return Number of bytes read, or PICO_ERROR_GENERIC if address not acknowledged or no device present.
+ */
+int i2c_read_blocking(i2c_inst_t *i2c, uint8_t addr, uint8_t *dst, size_t len, bool nostop);
+
+
+/*! \brief Determine non-blocking write space available
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \return 0 if no space is available in the I2C to write more data. If return is nonzero, at
+ * least that many bytes can be written without blocking.
+ */
+static inline size_t i2c_get_write_available(i2c_inst_t *i2c) {
+ const size_t IC_TX_BUFFER_DEPTH = 16;
+ return IC_TX_BUFFER_DEPTH - i2c_get_hw(i2c)->txflr;
+}
+
+/*! \brief Determine number of bytes received
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \return 0 if no data available, if return is nonzero at
+ * least that many bytes can be read without blocking.
+ */
+static inline size_t i2c_get_read_available(i2c_inst_t *i2c) {
+ return i2c_get_hw(i2c)->rxflr;
+}
+
+/*! \brief Write direct to TX FIFO
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param src Data to send
+ * \param len Number of bytes to send
+ *
+ * Writes directly to the I2C TX FIFO which is mainly useful for
+ * slave-mode operation.
+ */
+static inline void i2c_write_raw_blocking(i2c_inst_t *i2c, const uint8_t *src, size_t len) {
+ for (size_t i = 0; i < len; ++i) {
+ // TODO NACK or STOP on end?
+ while (!i2c_get_write_available(i2c))
+ tight_loop_contents();
+ i2c_get_hw(i2c)->data_cmd = *src++;
+ }
+}
+
+/*! \brief Read direct from RX FIFO
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param dst Buffer to accept data
+ * \param len Number of bytes to read
+ *
+ * Reads directly from the I2C RX FIFO which is mainly useful for
+ * slave-mode operation.
+ */
+static inline void i2c_read_raw_blocking(i2c_inst_t *i2c, uint8_t *dst, size_t len) {
+ for (size_t i = 0; i < len; ++i) {
+ while (!i2c_get_read_available(i2c))
+ tight_loop_contents();
+ *dst++ = (uint8_t)i2c_get_hw(i2c)->data_cmd;
+ }
+}
+
+/*! \brief Return the DREQ to use for pacing transfers to/from a particular I2C instance
+ * \ingroup hardware_i2c
+ *
+ * \param i2c Either \ref i2c0 or \ref i2c1
+ * \param is_tx true for sending data to the I2C instance, false for receiving data from the I2C instance
+ */
+static inline uint i2c_get_dreq(i2c_inst_t *i2c, bool is_tx) {
+ static_assert(DREQ_I2C0_RX == DREQ_I2C0_TX + 1, "");
+ static_assert(DREQ_I2C1_RX == DREQ_I2C1_TX + 1, "");
+ static_assert(DREQ_I2C1_TX == DREQ_I2C0_TX + 2, "");
+ return DREQ_I2C0_TX + i2c_hw_index(i2c) * 2 + !is_tx;
+}
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif