pw_spi: Introduce SPI HAL
This change introduces a new SPI HAL API, featuring abstractions
enabling a target device to communicate with SPI peripherals in
a portable and consistent fashion.
Change-Id: Idc085c4727abb9247732c40cc84d05ee4113bd78
Reviewed-on: https://pigweed-review.googlesource.com/c/pigweed/pigweed/+/70140
Reviewed-by: Ewout van Bekkum <ewout@google.com>
Reviewed-by: Keir Mierle <keir@google.com>
Commit-Queue: Mark Slevinsky <markslevinsky@google.com>
diff --git a/pw_spi/BUILD.bazel b/pw_spi/BUILD.bazel
new file mode 100644
index 0000000..217f7d4
--- /dev/null
+++ b/pw_spi/BUILD.bazel
@@ -0,0 +1,101 @@
+# Copyright 2020 The Pigweed Authors
+#
+# Licensed under the Apache License, Version 2.0 (the "License"); you may not
+# use this file except in compliance with the License. You may obtain a copy of
+# the License at
+#
+# https://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+# License for the specific language governing permissions and limitations under
+# the License.
+
+load(
+ "//pw_build:pigweed.bzl",
+ "pw_cc_library",
+ "pw_cc_test",
+)
+
+package(default_visibility = ["//visibility:public"])
+
+licenses(["notice"])
+
+pw_cc_library(
+ name = "initiator",
+ hdrs = [
+ "public/pw_spi/initiator.h",
+ ],
+ includes = ["public"],
+ deps = [
+ "//pw_assert",
+ "//pw_bytes",
+ "//pw_status",
+ ],
+)
+
+pw_cc_library(
+ name = "chip_selector",
+ hdrs = [
+ "public/pw_spi/chip_selector.h",
+ ],
+ includes = ["public"],
+ deps = [
+ "//pw_status",
+ ],
+)
+
+pw_cc_library(
+ name = "device",
+ hdrs = [
+ "public/pw_spi/device.h",
+ ],
+ includes = ["public"],
+ deps = [
+ ":chip_selector",
+ ":initiator",
+ "//pw_bytes",
+ "//pw_chrono:system_clock",
+ "//pw_status",
+ "//pw_sync:borrow",
+ ],
+)
+
+pw_cc_test(
+ name = "spi_test",
+ srcs = [
+ "spi_test.cc",
+ ],
+ deps = [
+ ":device",
+ "//pw_sync:mutex",
+ "//pw_unit_test",
+ ],
+)
+
+# Linux-specific spidev implementation.
+pw_cc_library(
+ name = "linux_spi",
+ srcs = ["linux_spi.cc"],
+ hdrs = ["public/pw_spi/linux_spi.h"],
+ includes = ["public"],
+ deps = [
+ ":device",
+ "//pw_bytes",
+ "//pw_chrono:system_clock",
+ "//pw_log",
+ "//pw_status",
+ "//pw_sync:borrow",
+ "//pw_sync:mutex",
+ ],
+)
+
+pw_cc_test(
+ name = "linux_spi_test",
+ srcs = ["linux_spi_test.cc"],
+ deps = [
+ ":device",
+ ":linux_spi",
+ ],
+)
diff --git a/pw_spi/BUILD.gn b/pw_spi/BUILD.gn
new file mode 100644
index 0000000..3c46fc9
--- /dev/null
+++ b/pw_spi/BUILD.gn
@@ -0,0 +1,103 @@
+# Copyright 2021 The Pigweed Authors
+#
+# Licensed under the Apache License, Version 2.0 (the "License"); you may not
+# use this file except in compliance with the License. You may obtain a copy of
+# the License at
+#
+# https://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+# License for the specific language governing permissions and limitations under
+# the License.
+
+import("//build_overrides/pigweed.gni")
+
+import("$dir_pw_build/target_types.gni")
+import("$dir_pw_docgen/docs.gni")
+import("$dir_pw_unit_test/test.gni")
+
+config("public_include_path") {
+ include_dirs = [ "public" ]
+}
+
+group("pw_spi") {
+ deps = [
+ ":chip_selector",
+ ":device",
+ ":initiator",
+ ]
+ if (host_os == "linux") {
+ deps += [ ":linux_spi" ]
+ }
+}
+
+pw_source_set("initiator") {
+ public_configs = [ ":public_include_path" ]
+ public = [ "public/pw_spi/initiator.h" ]
+ public_deps = [
+ "$dir_pw_assert",
+ "$dir_pw_bytes",
+ "$dir_pw_status",
+ ]
+}
+
+pw_source_set("chip_selector") {
+ public_configs = [ ":public_include_path" ]
+ public = [ "public/pw_spi/chip_selector.h" ]
+ public_deps = [ "$dir_pw_status" ]
+}
+
+pw_source_set("device") {
+ public_configs = [ ":public_include_path" ]
+ public = [ "public/pw_spi/device.h" ]
+ public_deps = [
+ ":chip_selector",
+ ":initiator",
+ "$dir_pw_bytes",
+ "$dir_pw_status",
+ "$dir_pw_sync:borrow",
+ ]
+}
+
+# Linux-specific spidev implementation.
+pw_source_set("linux_spi") {
+ public_configs = [ ":public_include_path" ]
+ public = [ "public/pw_spi/linux_spi.h" ]
+ public_deps = [
+ ":device",
+ "$dir_pw_bytes",
+ "$dir_pw_log",
+ "$dir_pw_status",
+ "$dir_pw_sync:borrow",
+ "$dir_pw_sync:mutex",
+ ]
+ sources = [ "linux_spi.cc" ]
+}
+
+pw_test_group("tests") {
+ tests = [ ":spi_test" ]
+}
+
+pw_test("spi_test") {
+ sources = [ "spi_test.cc" ]
+ deps = [
+ ":device",
+ "$dir_pw_sync:mutex",
+ ]
+}
+
+# Linux tests currently only work on a target with spidev support and a SPI endpoint
+# mounted at /dev/spidev0.0
+pw_test("linux_spi_test") {
+ sources = [ "linux_spi_test.cc" ]
+ deps = [
+ ":device",
+ ":linux_spi",
+ ]
+}
+
+pw_doc_group("docs") {
+ sources = [ "docs.rst" ]
+}
diff --git a/pw_spi/docs.rst b/pw_spi/docs.rst
new file mode 100644
index 0000000..6332e11
--- /dev/null
+++ b/pw_spi/docs.rst
@@ -0,0 +1,338 @@
+.. _module-pw_spi:
+
+======
+pw_spi
+======
+Pigweed's SPI module provides a set of interfaces for communicating with SPI
+peripherals attached to a target.
+
+--------
+Overview
+--------
+The ``pw_spi`` module provides a series of interfaces that facilitate the
+development of SPI peripheral drivers that are abstracted from the target's
+SPI hardware implementation. The interface consists of three main classes:
+
+- ``pw::spi::Initiator`` - Interface for configuring a SPI bus, and using it
+ to transmit and receive data.
+- ``pw::spi::ChipSelector`` - Interface for enabling/disabling a SPI
+ peripheral attached to the bus.
+- ``pw::spi::Device`` - primary HAL interface used to interact with a SPI
+ peripheral.
+
+``pw_spi`` relies on a target-specific implementations of
+``pw::spi::Initiator`` and ``pw::spi::ChipSelector`` to be defined, and
+injected into ``pw::spi::Device`` objects which are used to communicate with a
+given peripheral attached to a target's SPI bus.
+
+Example - Constructing a SPI Device:
+
+.. code-block:: cpp
+
+ constexpr pw::spi::Config kConfig = {
+ .polarity = pw::spi::ClockPolarity::kActiveHigh,
+ .phase = pw::spi::ClockPhase::kRisingEdge,
+ .bits_per_word = pw::spi::BitsPerWord(8),
+ .bit_order = pw::spi::BitOrder::kLsbFirst,
+ };
+
+ auto initiator = pw::spi::MyInitator();
+ auto selector = pw::spi::MyChipSelector();
+ auto borrowable_initiator = pw::sync::Borrowable<Initiator&>(initiator);
+
+ auto device = pw::spi::Device(borrowable_initiator, kConfig, selector);
+
+This example demonstrates the construction of a ``pw::spi::Device`` from its
+object dependencies and configuration data; where ``MyDevice`` and
+`MyChipSelector`` are concrete implementations of the ``pw::spi::Initiator``
+and ``pw::spi::ChipSelector`` interfaces, respectively.
+
+The use of ``pw::sync::Borrowable`` in the interface provides a
+mutual-exclusion wrapper for the the injected ``pw::spi::Initiator``, ensuring
+that transactions cannot be interrupted or corrupted by other concurrent
+workloads making use of the same SPI bus.
+
+Once constructed, the ``device`` object can then be passed to functions used to
+perform SPI transfers with a target peripheral.
+
+Example - Performing a Transfer:
+
+.. code-block:: cpp
+
+ pw::Result<SensorData> ReadSensorData(pw::spi::Device& device) {
+ std::array<std::byte, 16> raw_sensor_data;
+ constexpr std::array<std::byte, 2> kAccelReportCommand = {
+ std::byte{0x13}, std::byte{0x37}};
+
+ // This device supports full-duplex transfers
+ PW_TRY(device.WriteRead(kAccelReportCommand, raw_sensor_data));
+ return UnpackSensorData(raw_sensor_data);
+ }
+
+The ``ReadSensorData()`` function implements a driver function for a contrived
+SPI accelerometer. The function performs a full-duplex transfer with the
+device to read its current data.
+
+As this function relies on the ``device`` object that abstracts the details
+of bus-access and chip-selection, the function is portable to any target
+that implements its underlying interfaces.
+
+Example - Performing a Multi-part Transaction:
+
+.. code-block:: cpp
+
+ pw::Result<SensorData> ReadSensorData(pw::spi::Device& device) {
+ std::array<std::byte, 16> raw_sensor_data;
+ constexpr std::array<std::byte, 2> kAccelReportCommand = {
+ std::byte{0x13}, std::byte{0x37}};
+
+ // Creation of the RAII `transaction` acquires exclusive access to the bus
+ std::optional<pw::spi::Device::Transaction> transaction =
+ device.StartTransaction(pw::spi::ChipSelectBehavior::kPerTransaction);
+ if (!transaction.has_value()) {
+ return pw::Status::Unknown();
+ )
+
+ // This device only supports half-duplex transfers
+ PW_TRY(transaction->Write(kAccelReportCommand));
+ PW_TRY(transaction->Read(raw_sensor_data))
+
+ return UnpackSensorData(raw_sensor_data);
+
+ // Destruction of RAII `transaction` object releases lock on the bus
+ }
+
+The code above is similar to the previous example, but makes use of the
+``Transaction`` API in ``pw::spi::Device`` to perform separate, half-duplex
+``Write()`` and ``Read()`` transfers, as is required by the sensor in this
+examplre.
+
+The use of the RAII ``transaction`` object in this example guarantees that
+no other thread can perform transfers on the same SPI bus
+(``pw::spi::Initiator``) until it goes out-of-scope.
+
+------------------
+pw::spi Interfaces
+------------------
+The SPI API consists of the following components:
+
+- The ``pw::spi::Initiator`` interface, and its associated configuration data
+ structs.
+- The ``pw::spi::ChipSelector`` interface.
+- The ``pw::spi::Device`` class.
+
+pw::spi::Initiator
+------------------
+.. inclusive-language: disable
+
+The common interface for configuring a SPI bus, and initiating transfers using
+it.
+
+A concrete implementation of this interface class *must* be defined in order
+to use ``pw_spi`` with a specific target.
+
+The ``spi::Initiator`` object configures the SPI bus to communicate with a
+defined set of common bus parameters that include:
+
+- clock polarity/phase
+- bits-per-word (between 3-32 bits)
+- bit ordering (LSB or MSB first)
+
+These bus configuration parameters are aggregated in the ``pw::spi::Config``
+structure, and passed to the ``pw::spi::Initiator`` via its ``Configure()``
+method.
+
+.. Note:
+
+ Throughtout ``pw_spi``, the terms "controller" and "peripheral" are used to
+ describe the two roles SPI devices can implement. These terms correspond
+ to the "master" and "slave" roles described in legacy documentation
+ related to the SPI protocol.
+
+ ``pw_spi`` only supports SPI transfers where the target implements the
+ "controller" role, and does not support the target acting in the
+ "peripheral" role.
+
+.. inclusive-language: enable
+
+.. cpp:class:: pw::spi::Initiator
+
+ .. cpp:function:: Status Configure(const Config& config)
+
+ Configure the SPI bus to coummunicate using a specific set of properties,
+ including the clock polarity, clock phase, bit-order, and bits-per-word.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure conditions
+
+ .. cpp:function:: Status WriteRead(ConstByteSpan write_buffer, ByteSpan read_buffer) = 0;
+
+ Perform a synchronous read/write operation on the SPI bus. Data from the
+ `write_buffer` object is written to the bus, while the `read_buffer` is
+ populated with incoming data on the bus. The operation will ensure that
+ all requested data is written-to and read-from the bus. In the event the
+ read buffer is smaller than the write buffer (or zero-size), any
+ additional input bytes are discarded. In the event the write buffer is
+ smaller than the read buffer (or zero size), the output is padded with
+ 0-bits for the remainder of the transfer.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+pw::spi::ChipSelector
+---------------------
+The ChipSelector class provides an abstract interface for controlling the
+chip-select signal associated with a specific SPI peripheral.
+
+This interface provides a ``SetActive()`` method, which activates/deactivates
+the device based on the value of the `active` parameter. The associated
+``Activate()`` and ``Deactivate()`` methods are utility wrappers for
+``SetActive(true)`` and ``SetActive(false)``, respectively.
+
+A concrete implementation of this interface class must be provided in order to
+use the SPI HAL to communicate with a peripheral.
+
+.. Note::
+
+ `Active` does not imply a specific logic-level; it is left to the
+ implementor to correctly map logic-levels to the device's active/inactive
+ states.
+
+.. cpp:class:: pw::spi::ChipSelector
+
+ .. cpp:function:: Status SetActive(bool active)
+
+ SetActive sets the state of the chip-select signal to the value
+ represented by the `active` parameter. Passing a value of `true` will
+ activate the chip-select signal, and `false` will deactive the
+ chip-select signal.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+ .. cpp:function:: Status Activate()
+
+ Helper method to activate the chip-select signal
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+ .. cpp:function:: Status Deactivate()
+
+ Helper method to deactivate the chip-select signal
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+pw::spi::Device
+---------------
+This is primary object used by a client to interact with a target SPI device.
+It provides a wrapper for an injected ``pw::spi::Initator`` object, using
+its methods to configure the bus and perform individual SPI transfers. The
+injected ``pw::spi::ChipSelector`` object is used internally to activate and
+de-actviate the device on-demand from within the data transfer methods.
+
+The ``Read()``/``Write()``/``WriteRead()`` methods provide support for
+performing inidividual transfers: ``Read()`` and ``Write()`` perform
+half-duplex operations, where ``WriteRead()`` provides support for
+full-duplex transfers.
+
+The ``StartTransaction()`` method provides support for performing multi-part
+transfers consisting of a series of ``Read()``/``Write()``/``WriteRead()``
+calls, during which the caller is guaranteed exclusive access to the
+underlying bus. The ``Transaction`` objects returned from this method
+implements the RAII layer providing exclusive access to the bus; exclusive
+access locking is released when the ``Transaction`` object is destroyed/goes
+out of scope.
+
+Mutual-exclusion to the ``pw::spi::Initiator`` object is provided by the use of
+the ``pw::sync::Borrowable`` object, where the ``pw::spi::Initiator`` object is
+"borrowed" for the duration of a transaction.
+
+.. cpp:class:: pw::spi::Device
+
+ .. cpp:function:: Status Read(Bytespan read_buffer)
+
+ Synchronously read data from the SPI peripheral until the provided
+ `read_buffer` is full.
+ This call will configure the bus and activate/deactive chip select
+ for the transfer
+
+ Note: This call will block in the event that other clients are currently
+ performing transactions using the same SPI Initiator.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+ .. cpp:function:: Status Write(ConstByteSpan write_buffer)
+
+ Synchronously write the contents of `write_buffer` to the SPI peripheral.
+ This call will configure the bus and activate/deactive chip select
+ for the transfer
+
+ Note: This call will block in the event that other clients are currently
+ performing transactions using the same SPI Initiator.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+ .. cpp:function:: Status WriteRead(ConstByteSpan write_buffer, ByteSpan read_buffer)
+
+ Perform a synchronous read/write transfer with the SPI peripheral. Data
+ from the `write_buffer` object is written to the bus, while the
+ `read_buffer` is populated with incoming data on the bus. In the event
+ the read buffer is smaller than the write buffer (or zero-size), any
+ additional input bytes are discarded. In the event the write buffer is
+ smaller than the read buffer (or zero size), the output is padded with
+ 0-bits for the remainder of the transfer.
+ This call will configure the bus and activate/deactive chip select
+ for the transfer
+
+ Note: This call will block in the event that other clients are currently
+ performing transactions using the same SPI Initiator.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+ .. cpp:function:: Transaction StartTransaction(ChipSelectBehavior behavior)
+
+ Begin a transaction with the SPI device. This creates an RAII
+ `Transaction` object that ensures that only one entity can access the
+ underlying SPI bus (Initiator) for the object's duration. The `behavior`
+ parameter provides a means for a client to select how the chip-select
+ signal will be applied on Read/Write/WriteRead calls taking place with
+ the Transaction object. A value of `kPerWriteRead` will activate/deactive
+ chip-select on each operation, while `kPerTransaction` will hold the
+ chip-select active for the duration of the Transaction object.
+
+.. cpp:class:: pw::spi::Device::Transaction
+
+ .. cpp:function:: Status Read(Bytespan read_buffer)
+
+ Synchronously read data from the SPI peripheral until the provided
+ `read_buffer` is full.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+ .. cpp:function:: Status Write(ConstByteSpan write_buffer)
+
+ Synchronously write the contents of `write_buffer` to the SPI peripheral
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
+ .. cpp:function:: Status WriteRead(ConstByteSpan write_buffer, ByteSpan read_buffer)
+
+ Perform a synchronous read/write transfer on the SPI bus. Data from the
+ `write_buffer` object is written to the bus, while the `read_buffer` is
+ populated with incoming data on the bus. The operation will ensure that
+ all requested data is written-to and read-from the bus. In the event the
+ read buffer is smaller than the write buffer (or zero-size), any
+ additional input bytes are discarded. In the event the write buffer is
+ smaller than the read buffer (or zero size), the output is padded with
+ 0-bits for the remainder of the transfer.
+
+ Returns OkStatus() on success, and implementation-specific values on
+ failure.
+
diff --git a/pw_spi/linux_spi.cc b/pw_spi/linux_spi.cc
new file mode 100644
index 0000000..89a6c07
--- /dev/null
+++ b/pw_spi/linux_spi.cc
@@ -0,0 +1,124 @@
+// Copyright 2021 The Pigweed Authors
+//
+// Licensed under the Apache License, Version 2.0 (the "License"); you may not
+// use this file except in compliance with the License. You may obtain a copy of
+// the License at
+//
+// https://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+// License for the specific language governing permissions and limitations under
+// the License.
+
+#include "pw_spi/linux_spi.h"
+
+#include <fcntl.h>
+#include <linux/spi/spidev.h>
+#include <linux/types.h>
+#include <sys/ioctl.h>
+#include <unistd.h>
+
+#include "pw_log/log.h"
+#include "pw_spi/chip_selector.h"
+#include "pw_spi/device.h"
+#include "pw_spi/initiator.h"
+#include "pw_status/try.h"
+
+namespace pw::spi {
+
+LinuxInitiator::~LinuxInitiator() {
+ if (fd_ >= 0) {
+ close(fd_);
+ }
+}
+
+Status LinuxInitiator::LazyInit() {
+ if (fd_ >= 0) {
+ return OkStatus();
+ }
+ fd_ = open(path_, O_RDWR | O_EXCL);
+ if (fd_ < 0) {
+ PW_LOG_ERROR("Unable to open SPI device %s for read/write", path_);
+ return Status::Unavailable();
+ }
+ return OkStatus();
+}
+
+Status LinuxInitiator::Configure(const Config& config) {
+ PW_TRY(LazyInit());
+
+ // Map clock polarity/phase to Linux userspace equivalents
+ uint32_t mode = 0;
+ if (config.polarity == ClockPolarity::kActiveLow) {
+ mode |= SPI_CPOL; // Clock polarity -- signal is high when idle
+ }
+ if (config.phase == ClockPhase::kFallingEdge) {
+ mode |= SPI_CPHA; // Clock phase -- latch on falling edge
+ }
+ if (ioctl(fd_, SPI_IOC_WR_MODE32, &mode) < 0) {
+ PW_LOG_ERROR("Unable to set SPI mode");
+ return Status::InvalidArgument();
+ }
+
+ // Configure LSB/MSB first
+ uint8_t lsb_first = 0;
+ if (config.bit_order == BitOrder::kLsbFirst) {
+ lsb_first = 1; // non-zero value indicates LSB first
+ }
+ if (ioctl(fd_, SPI_IOC_WR_LSB_FIRST, &lsb_first) < 0) {
+ PW_LOG_ERROR("Unable to set SPI LSB");
+ return Status::InvalidArgument();
+ }
+
+ // Configure bits-per-word
+ uint8_t bits_per_word = config.bits_per_word();
+ if (ioctl(fd_, SPI_IOC_WR_BITS_PER_WORD, &bits_per_word) < 0) {
+ PW_LOG_ERROR("Unable to set SPI Bits Per Word");
+ return Status::InvalidArgument();
+ }
+
+ // Configure maximum bus speed
+ if (ioctl(fd_, SPI_IOC_WR_MAX_SPEED_HZ, &max_speed_hz_) < 0) {
+ PW_LOG_ERROR("Unable to set SPI Max Speed");
+ return Status::InvalidArgument();
+ }
+
+ return OkStatus();
+}
+
+Status LinuxInitiator::WriteRead(ConstByteSpan write_buffer,
+ ByteSpan read_buffer) {
+ PW_TRY(LazyInit());
+
+ // Configure a full-duplex transfer using ioctl()
+ struct spi_ioc_transfer transaction[2];
+ memset(transaction, 0, sizeof(transaction));
+ transaction[0].tx_buf = reinterpret_cast<uintptr_t>(write_buffer.data());
+ transaction[0].len = write_buffer.size();
+
+ transaction[1].rx_buf = reinterpret_cast<uintptr_t>(read_buffer.data());
+ transaction[1].len = read_buffer.size();
+
+ if (ioctl(fd_, SPI_IOC_MESSAGE(2), transaction) < 0) {
+ PW_LOG_ERROR("Unable to perform SPI transfer");
+ return Status::Unknown();
+ }
+
+ return OkStatus();
+}
+
+Status LinuxChipSelector::SetActive(bool /*active*/) {
+ // Note: For Linux' SPI userspace support, chip-select control is not exposed
+ // directly to the user. This limits our ability to use the SPI HAL to do
+ // composite (multi read-write) transactions with the PW SPI HAL, as Linux
+ // performs composite transactions with a single ioctl() call using an array
+ // of descriptors provided as a parameter -- there's no way of separating
+ // individual operations from userspace. This could be addressed with a
+ // direct "Composite" transaction HAL API, or by using a raw GPIO
+ // to control of chip select from userspace (which is not common practice).
+ return OkStatus();
+}
+
+} // namespace pw::spi
diff --git a/pw_spi/linux_spi_test.cc b/pw_spi/linux_spi_test.cc
new file mode 100644
index 0000000..23a881b
--- /dev/null
+++ b/pw_spi/linux_spi_test.cc
@@ -0,0 +1,101 @@
+// Copyright 2021 The Pigweed Authors
+//
+// Licensed under the Apache License, Version 2.0 (the "License"); you may not
+// use this file except in compliance with the License. You may obtain a copy of
+// the License at
+//
+// https://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+// License for the specific language governing permissions and limitations under
+// the License.
+
+#include "pw_spi/linux_spi.h"
+
+#include <array>
+#include <optional>
+
+#include "gtest/gtest.h"
+#include "pw_spi/chip_selector.h"
+#include "pw_spi/device.h"
+#include "pw_spi/initiator.h"
+#include "pw_status/status.h"
+#include "pw_sync/borrow.h"
+
+namespace pw::spi {
+namespace {
+
+const pw::spi::Config kConfig = {.polarity = ClockPolarity::kActiveHigh,
+ .phase = ClockPhase::kFallingEdge,
+ .bits_per_word = BitsPerWord(8),
+ .bit_order = BitOrder::kMsbFirst};
+
+class LinuxSpi : public ::testing::Test {
+ public:
+ LinuxSpi()
+ : initiator_(LinuxInitiator("/dev/spidev0.0", 1000000)),
+ chip_selector_(),
+ initiator_lock_(),
+ borrowable_initiator_(initiator_, initiator_lock_),
+ device_(borrowable_initiator_, kConfig, chip_selector_) {}
+
+ Device& device() { return device_; }
+
+ private:
+ LinuxInitiator initiator_;
+ LinuxChipSelector chip_selector_;
+ sync::VirtualMutex initiator_lock_;
+ sync::Borrowable<Initiator> borrowable_initiator_;
+ [[maybe_unused]] Device device_;
+};
+
+TEST_F(LinuxSpi, StartTransaction_Succeeds) {
+ // arrange
+ std::optional<Device::Transaction> transaction =
+ device().StartTransaction(ChipSelectBehavior::kPerWriteRead);
+
+ // act
+
+ // assert
+ EXPECT_TRUE(transaction.has_value());
+}
+
+TEST_F(LinuxSpi, HalfDuplexTransaction_Succeeds) {
+ // arrange
+ std::optional<Device::Transaction> transaction =
+ device().StartTransaction(ChipSelectBehavior::kPerWriteRead);
+
+ // act
+ ASSERT_TRUE(transaction.has_value());
+
+ std::array write_data{std::byte(1), std::byte(2), std::byte(3), std::byte(4)};
+ auto write_status = transaction->Write(ConstByteSpan(write_data));
+
+ std::array read_data{std::byte(1), std::byte(2), std::byte(3), std::byte(4)};
+ auto read_status = transaction->Read(read_data);
+
+ // assert
+ EXPECT_TRUE(write_status.ok());
+ EXPECT_TRUE(read_status.ok());
+}
+
+TEST_F(LinuxSpi, FullDuplexTransaction_Succeeds) {
+ // arrange
+ std::optional<Device::Transaction> transaction =
+ device().StartTransaction(ChipSelectBehavior::kPerWriteRead);
+
+ // act
+ ASSERT_TRUE(transaction.has_value());
+
+ std::array write_data{std::byte(1), std::byte(2), std::byte(3), std::byte(4)};
+ std::array read_data{std::byte(0), std::byte(0), std::byte(0), std::byte(0)};
+ auto wr_status = transaction->WriteRead(ConstByteSpan(write_data), read_data);
+
+ // assert
+ EXPECT_TRUE(wr_status.ok());
+}
+
+} // namespace
+} // namespace pw::spi
diff --git a/pw_spi/public/pw_spi/chip_selector.h b/pw_spi/public/pw_spi/chip_selector.h
new file mode 100644
index 0000000..4792623
--- /dev/null
+++ b/pw_spi/public/pw_spi/chip_selector.h
@@ -0,0 +1,56 @@
+// Copyright 2021 The Pigweed Authors
+//
+// Licensed under the Apache License, Version 2.0 (the "License"); you may not
+// use this file except in compliance with the License. You may obtain a copy of
+// the License at
+//
+// https://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+// License for the specific language governing permissions and limitations under
+// the License.
+
+#pragma once
+
+#include <cstdint>
+
+#include "pw_status/status.h"
+
+namespace pw::spi {
+
+// Configuration data used to determine how the Chip Select signal is controlled
+// throughout a transaction.
+// `kPerWriteRead` indicates that the chip-select signal should be
+// activated/deactivated between calls to WriteRead()
+enum class ChipSelectBehavior : uint8_t {
+ kPerWriteRead,
+ kPerTransaction,
+};
+
+// The ChipSelector class provides an abstract interface for controlling the
+// chip-select signal associated with a specific SPI peripheral.
+class ChipSelector {
+ public:
+ virtual ~ChipSelector() = default;
+
+ // SetActive sets the state of the chip-select signal to the value represented
+ // by the `active` parameter. Passing a value of `true` will activate the
+ // chip-select signal, and `false` will deactive the chip-select signal.
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ virtual Status SetActive(bool active) = 0;
+
+ // Helper method to activate the chip-select signal
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status Activate() { return SetActive(true); }
+
+ // Helper method to deactivate the chip-select signal
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status Deactivate() { return SetActive(false); }
+};
+
+} // namespace pw::spi
diff --git a/pw_spi/public/pw_spi/device.h b/pw_spi/public/pw_spi/device.h
new file mode 100644
index 0000000..07a9858
--- /dev/null
+++ b/pw_spi/public/pw_spi/device.h
@@ -0,0 +1,207 @@
+// Copyright 2021 The Pigweed Authors
+//
+// Licensed under the Apache License, Version 2.0 (the "License"); you may not
+// use this file except in compliance with the License. You may obtain a copy of
+// the License at
+//
+// https://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+// License for the specific language governing permissions and limitations under
+// the License.
+
+#pragma once
+
+#include <optional>
+
+#include "pw_bytes/span.h"
+#include "pw_spi/chip_selector.h"
+#include "pw_spi/initiator.h"
+#include "pw_status/status.h"
+#include "pw_status/try.h"
+#include "pw_sync/borrow.h"
+
+namespace pw::spi {
+
+// The Device class enables data transfer with a specific SPI peripheral.
+// This class combines an Initiator (representing the physical SPI bus), its
+// configuration data, and the ChipSelector object to uniquely address a device.
+// Transfers to a selected initiator are guarded against concurrent access
+// through the use of the `Borrowable` object.
+class Device {
+ public:
+ Device(sync::Borrowable<Initiator>& initiator,
+ const Config config,
+ ChipSelector& selector)
+ : initiator_(initiator), config_(config), selector_(selector) {}
+
+ ~Device() = default;
+
+ // Synchronously read data from the SPI peripheral until the provided
+ // `read_buffer` is full.
+ // This call will configure the bus and activate/deactive chip select
+ // for the transfer
+ //
+ // Note: This call will block in the event that other clients are currently
+ // performing transactions using the same SPI Initiator.
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status Read(ByteSpan read_buffer) { return WriteRead({}, read_buffer); }
+
+ // Synchronously write the contents of `write_buffer` to the SPI peripheral.
+ // This call will configure the bus and activate/deactive chip select
+ // for the transfer
+ //
+ // Note: This call will block in the event that other clients are currently
+ // performing transactions using the same SPI Initiator.
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status Write(ConstByteSpan write_buffer) {
+ return WriteRead(write_buffer, {});
+ }
+
+ // Perform a synchronous read/write transfer with the SPI peripheral. Data
+ // from the `write_buffer` object is written to the bus, while the
+ // `read_buffer` is populated with incoming data on the bus. In the event
+ // the read buffer is smaller than the write buffer (or zero-size), any
+ // additional input bytes are discarded. In the event the write buffer is
+ // smaller than the read buffer (or zero size), the output is padded with
+ // 0-bits for the remainder of the transfer.
+ // This call will configure the bus and activate/deactive chip select
+ // for the transfer
+ //
+ // Note: This call will block in the event that other clients
+ // are currently performing transactions using the same SPI Initiator.
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status WriteRead(ConstByteSpan write_buffer, ByteSpan read_buffer) {
+ return StartTransaction(ChipSelectBehavior::kPerWriteRead)
+ .WriteRead(write_buffer, read_buffer);
+ }
+
+ // RAII Object providing exclusive access to the SPI device. Enables
+ // thread-safe Read()/Write()/WriteRead() operations, as well as composite
+ // operations consisting of multiple, uninterrupted transfers, with
+ // configurable chip-select behavior.
+ class Transaction final {
+ public:
+ Transaction() = delete;
+ ~Transaction() {
+ if ((selector_ != nullptr) &&
+ (behavior_ == ChipSelectBehavior::kPerTransaction) &&
+ (!first_write_read_)) {
+ selector_->Deactivate();
+ }
+ }
+
+ // Transaction objects are moveable but not copyable
+ Transaction(Transaction&& other)
+ : initiator_(std::move(other.initiator_)),
+ config_(other.config_),
+ selector_(other.selector_),
+ behavior_(other.behavior_),
+ first_write_read_(other.first_write_read_) {
+ other.selector_ = nullptr;
+ };
+
+ Transaction& operator=(Transaction&& other) {
+ initiator_ = std::move(other.initiator_);
+ config_ = other.config_;
+ selector_ = other.selector_;
+ other.selector_ = nullptr;
+ behavior_ = other.behavior_;
+ first_write_read_ = other.first_write_read_;
+ return *this;
+ }
+
+ Transaction(const Transaction&) = delete;
+ Transaction& operator=(const Transaction&) = delete;
+
+ // Synchronously read data from the SPI peripheral until the provided
+ // `read_buffer` is full.
+ //
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status Read(ByteSpan read_buffer) { return WriteRead({}, read_buffer); }
+
+ // Synchronously write the contents of `write_buffer` to the SPI peripheral
+ //
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status Write(ConstByteSpan write_buffer) {
+ return WriteRead(write_buffer, {});
+ }
+
+ // Perform a synchronous read/write transfer on the SPI bus. Data from the
+ // `write_buffer` object is written to the bus, while the `read_buffer` is
+ // populated with incoming data on the bus. The operation will ensure that
+ // all requested data is written-to and read-from the bus. In the event the
+ // read buffer is smaller than the write buffer (or zero-size), any
+ // additional input bytes are discarded. In the event the write buffer is
+ // smaller than the read buffer (or zero size), the output is padded with
+ // 0-bits for the remainder of the transfer.
+ //
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ Status WriteRead(ConstByteSpan write_buffer, ByteSpan read_buffer) {
+ // Lazy-init: Configure the SPI bus when performing the first transfer in
+ // a transaction.
+ if (first_write_read_) {
+ PW_TRY(initiator_->Configure(config_));
+ }
+
+ if ((behavior_ == ChipSelectBehavior::kPerWriteRead) ||
+ (first_write_read_)) {
+ PW_TRY(selector_->Activate());
+ first_write_read_ = false;
+ }
+
+ auto status = initiator_->WriteRead(write_buffer, read_buffer);
+
+ if (behavior_ == ChipSelectBehavior::kPerWriteRead) {
+ PW_TRY(selector_->Deactivate());
+ }
+
+ return status;
+ }
+
+ private:
+ friend Device;
+ explicit Transaction(sync::BorrowedPointer<Initiator> initiator,
+ const Config& config,
+ ChipSelector& selector,
+ ChipSelectBehavior& behavior)
+ : initiator_(std::move(initiator)),
+ config_(config),
+ selector_(&selector),
+ behavior_(behavior),
+ first_write_read_(true) {}
+
+ sync::BorrowedPointer<Initiator> initiator_;
+ Config config_;
+ ChipSelector* selector_;
+ ChipSelectBehavior behavior_;
+ bool first_write_read_;
+ };
+
+ // Begin a transaction with the SPI device. This creates an RAII
+ // `Transaction` object that ensures that only one entity can access the
+ // underlying SPI bus (Initiator) for the object's duration. The `behavior`
+ // parameter provides a means for a client to select how the chip-select
+ // signal will be applied on Read/Write/WriteRead calls taking place with the
+ // Transaction object. A value of `kPerWriteRead` will activate/deactive
+ // chip-select on each operation, while `kPerTransaction` will hold the
+ // chip-select active for the duration of the Transaction object.
+ Transaction StartTransaction(ChipSelectBehavior behavior) {
+ return Transaction(initiator_.acquire(), config_, selector_, behavior);
+ }
+
+ private:
+ sync::Borrowable<Initiator>& initiator_;
+ const Config config_;
+ ChipSelector& selector_;
+};
+
+} // namespace pw::spi
diff --git a/pw_spi/public/pw_spi/initiator.h b/pw_spi/public/pw_spi/initiator.h
new file mode 100644
index 0000000..cc826c2
--- /dev/null
+++ b/pw_spi/public/pw_spi/initiator.h
@@ -0,0 +1,101 @@
+// Copyright 2021 The Pigweed Authors
+//
+// Licensed under the Apache License, Version 2.0 (the "License"); you may not
+// use this file except in compliance with the License. You may obtain a copy of
+// the License at
+//
+// https://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+// License for the specific language governing permissions and limitations under
+// the License.
+
+#pragma once
+
+#include <cstdint>
+#include <type_traits>
+
+#include "pw_assert/assert.h"
+#include "pw_bytes/span.h"
+#include "pw_status/status.h"
+
+namespace pw::spi {
+
+// ClockPolarity is a configuration parameter that specifies whether a SPI
+// bus clock signal is active low, or active high.
+enum class ClockPolarity : uint8_t {
+ kActiveHigh, // Corresponds to CPOL = 0
+ kActiveLow, // Corresponds to CPOL = 1
+};
+
+// ClockPhase is a configuration parameter that specifies whether the
+// phase of the SPI bus clock is rising edge or falling edge.
+enum class ClockPhase : uint8_t {
+ kRisingEdge, // Corresponds to CPHA = 0
+ kFallingEdge, // Corresponds to CPHA = 1
+};
+
+// Configuration parameter, specifying the bit order for data clocked over the
+// SPI bus; whether least-significant bit first, or most-significant bit first
+enum class BitOrder : uint8_t {
+ kLsbFirst,
+ kMsbFirst,
+};
+
+// Configuration object used to represent the number of bits in a SPI
+// data word. Devices typically use 8-bit words, although values of 3-32
+// are sometimes specified for bus-level optimizations. Values outside
+// this range are considered an error.
+class BitsPerWord {
+ public:
+ constexpr BitsPerWord(uint8_t data_bits) : data_bits_(data_bits) {
+ PW_ASSERT(data_bits_ >= 3 && data_bits_ <= 32);
+ }
+
+ uint8_t operator()() const { return data_bits_; }
+
+ private:
+ uint8_t data_bits_;
+};
+
+// This struct contains the necessary configuration details required to
+// initialize a SPI bus for communication with a target device.
+struct Config {
+ ClockPolarity polarity;
+ ClockPhase phase;
+ BitsPerWord bits_per_word;
+ BitOrder bit_order;
+};
+static_assert(sizeof(Config) == sizeof(uint32_t),
+ "Ensure that the config struct fits in 32-bits");
+
+// The Inititor class provides an abstract interface used to configure and
+// transmit data using a SPI bus.
+class Initiator {
+ public:
+ virtual ~Initiator() = default;
+
+ // Configure the SPI bus to communicate with peripherals using a given set of
+ // properties, including the clock polarity, clock phase, bit-order, and
+ // bits-per-wrod.
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ virtual Status Configure(const Config& config) = 0;
+
+ // Perform a synchronous read/write operation on the SPI bus. Data from the
+ // `write_buffer` object is written to the bus, while the `read_buffer` is
+ // populated with incoming data on the bus. The operation will ensure that
+ // all requested data is written-to and read-from the bus. In the event the
+ // read buffer is smaller than the write buffer (or zero-size), any additional
+ // input bytes are discarded. In the event the write buffer is smaller than
+ // the read buffer (or zero size), the output is padded with 0-bits for the
+ // remainder of the transfer.
+ // Returns OkStatus() on success, and implementation-specific values on
+ // failure.
+ virtual Status WriteRead(ConstByteSpan write_buffer,
+ ByteSpan read_buffer) = 0;
+};
+
+} // namespace pw::spi
diff --git a/pw_spi/public/pw_spi/linux_spi.h b/pw_spi/public/pw_spi/linux_spi.h
new file mode 100644
index 0000000..27bfc1b
--- /dev/null
+++ b/pw_spi/public/pw_spi/linux_spi.h
@@ -0,0 +1,56 @@
+// Copyright 2021 The Pigweed Authors
+//
+// Licensed under the Apache License, Version 2.0 (the "License"); you may not
+// use this file except in compliance with the License. You may obtain a copy of
+// the License at
+//
+// https://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+// License for the specific language governing permissions and limitations under
+// the License.
+
+#pragma once
+
+#include <fcntl.h>
+#include <linux/spi/spidev.h>
+#include <linux/types.h>
+#include <sys/ioctl.h>
+#include <unistd.h>
+
+#include "pw_log/log.h"
+#include "pw_spi/chip_selector.h"
+#include "pw_spi/device.h"
+#include "pw_spi/initiator.h"
+namespace pw::spi {
+
+// Linux userspace implementation of the SPI Initiator
+class LinuxInitiator : public Initiator {
+ public:
+ // Configure the Linux Initiator object for use with a bus specified by path,
+ // with a maximum bus-speed (in hz).
+ constexpr LinuxInitiator(const char* path, uint32_t max_speed_hz)
+ : path_(path), max_speed_hz_(max_speed_hz), fd_(-1) {}
+ ~LinuxInitiator();
+
+ // Implements pw::spi::Initiator
+ Status Configure(const Config& config) override;
+ Status WriteRead(ConstByteSpan write_buffer, ByteSpan read_buffer) override;
+
+ private:
+ Status LazyInit();
+
+ const char* path_;
+ uint32_t max_speed_hz_;
+ int fd_;
+};
+
+// Linux userspace implementation of SPI ChipSelector
+class LinuxChipSelector : public ChipSelector {
+ public:
+ Status SetActive(bool active) override;
+};
+
+} // namespace pw::spi
diff --git a/pw_spi/spi_test.cc b/pw_spi/spi_test.cc
new file mode 100644
index 0000000..21e5178
--- /dev/null
+++ b/pw_spi/spi_test.cc
@@ -0,0 +1,75 @@
+// Copyright 2021 The Pigweed Authors
+//
+// Licensed under the Apache License, Version 2.0 (the "License"); you may not
+// use this file except in compliance with the License. You may obtain a copy of
+// the License at
+//
+// https://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
+// License for the specific language governing permissions and limitations under
+// the License.
+
+#include <array>
+#include <optional>
+
+#include "gtest/gtest.h"
+#include "pw_spi/chip_selector.h"
+#include "pw_spi/device.h"
+#include "pw_spi/initiator.h"
+#include "pw_status/status.h"
+#include "pw_sync/borrow.h"
+#include "pw_sync/mutex.h"
+
+namespace pw::spi {
+namespace {
+
+const pw::spi::Config kConfig = {.polarity = ClockPolarity::kActiveHigh,
+ .phase = ClockPhase::kFallingEdge,
+ .bits_per_word = BitsPerWord(8),
+ .bit_order = BitOrder::kMsbFirst};
+
+class SpiTestDevice : public ::testing::Test {
+ public:
+ SpiTestDevice()
+ : initiator_(),
+ chip_selector_(),
+ initiator_lock_(),
+ borrowable_initiator_(initiator_, initiator_lock_),
+ device_(borrowable_initiator_, kConfig, chip_selector_) {}
+
+ private:
+ // Stub SPI Initiator/ChipSelect objects, used to exercise public API surface.
+ class TestInitiator : public Initiator {
+ public:
+ Status Configure(const Config& /*config */) override { return OkStatus(); };
+ Status WriteRead(ConstByteSpan /* write_buffer */,
+ ByteSpan /* read_buffer */) override {
+ return OkStatus();
+ };
+ };
+
+ class TestChipSelector : public ChipSelector {
+ public:
+ Status SetActive(bool /*active*/) override { return OkStatus(); }
+ };
+
+ TestInitiator initiator_;
+ TestChipSelector chip_selector_;
+ sync::VirtualMutex initiator_lock_;
+ sync::Borrowable<Initiator> borrowable_initiator_;
+ Device device_;
+};
+
+// Simple test ensuring the SPI HAL compiles
+TEST_F(SpiTestDevice, CompilationSucceeds) {
+ // arrange
+ // act
+ // assert
+ EXPECT_TRUE(true);
+}
+
+} // namespace
+} // namespace pw::spi