From 162405479b89cb48eea0be802a2a1c227541e5b7 Mon Sep 17 00:00:00 2001
From: Daniel Agar <daniel@agar.ca>
Date: Mon, 20 May 2019 12:18:56 -0400
Subject: [PATCH] device drivers lib add linux spi support

---
 boards/px4/sitl/default.cmake          |   6 +-
 boards/px4/sitl/rtps.cmake             |   6 +-
 boards/px4/sitl/test.cmake             |   6 +-
 platforms/posix/cmake/sitl_tests.cmake |   2 +-
 src/lib/drivers/device/CMakeLists.txt  |   4 +-
 src/lib/drivers/device/posix/SPI.cpp   | 198 +++++++++++++++++++++++++
 src/lib/drivers/device/posix/SPI.hpp   | 139 ++++++++++++++++-
 src/systemcmds/tests/tests_main.c      |   3 +-
 8 files changed, 348 insertions(+), 16 deletions(-)
 create mode 100644 src/lib/drivers/device/posix/SPI.cpp

diff --git a/boards/px4/sitl/default.cmake b/boards/px4/sitl/default.cmake
index c2fd0bfa09..9c01209b5b 100644
--- a/boards/px4/sitl/default.cmake
+++ b/boards/px4/sitl/default.cmake
@@ -8,10 +8,10 @@ px4_add_board(
 
 	DRIVERS
 		#barometer # all available barometer drivers
-		batt_smbus
+		#batt_smbus
 		camera_trigger
-		differential_pressure # all available differential pressure drivers
-		distance_sensor # all available distance sensor drivers
+		#differential_pressure # all available differential pressure drivers
+		#distance_sensor # all available distance sensor drivers
 		gps
 		#imu # all available imu drivers
 		#magnetometer # all available magnetometer drivers
diff --git a/boards/px4/sitl/rtps.cmake b/boards/px4/sitl/rtps.cmake
index 266f0291b6..edb5bffaba 100644
--- a/boards/px4/sitl/rtps.cmake
+++ b/boards/px4/sitl/rtps.cmake
@@ -8,10 +8,10 @@ px4_add_board(
 
 	DRIVERS
 		#barometer # all available barometer drivers
-		batt_smbus
+		#batt_smbus
 		camera_trigger
-		differential_pressure # all available differential pressure drivers
-		distance_sensor # all available distance sensor drivers
+		#differential_pressure # all available differential pressure drivers
+		#distance_sensor # all available distance sensor drivers
 		gps
 		#imu # all available imu drivers
 		#magnetometer # all available magnetometer drivers
diff --git a/boards/px4/sitl/test.cmake b/boards/px4/sitl/test.cmake
index 3918af8166..ebf7e878e7 100644
--- a/boards/px4/sitl/test.cmake
+++ b/boards/px4/sitl/test.cmake
@@ -8,10 +8,10 @@ px4_add_board(
 
 	DRIVERS
 		#barometer # all available barometer drivers
-		batt_smbus
+		#batt_smbus
 		camera_trigger
-		differential_pressure # all available differential pressure drivers
-		distance_sensor # all available distance sensor drivers
+		#differential_pressure # all available differential pressure drivers
+		#distance_sensor # all available distance sensor drivers
 		gps
 		#imu # all available imu drivers
 		#magnetometer # all available magnetometer drivers
diff --git a/platforms/posix/cmake/sitl_tests.cmake b/platforms/posix/cmake/sitl_tests.cmake
index dcba66cb86..a0cef81b26 100644
--- a/platforms/posix/cmake/sitl_tests.cmake
+++ b/platforms/posix/cmake/sitl_tests.cmake
@@ -32,7 +32,7 @@ set(tests
 	rc
 	search_min
 	servo
-	sf0x
+	#sf0x
 	sleep
 	uorb
 	versioning
diff --git a/src/lib/drivers/device/CMakeLists.txt b/src/lib/drivers/device/CMakeLists.txt
index e6dca23d79..5162cb39ab 100644
--- a/src/lib/drivers/device/CMakeLists.txt
+++ b/src/lib/drivers/device/CMakeLists.txt
@@ -40,9 +40,11 @@ if (${PX4_PLATFORM} STREQUAL "nuttx")
 	if ("${CONFIG_SPI}" STREQUAL "y")
 		list(APPEND SRCS_PLATFORM nuttx/SPI.cpp)
 	endif()
-else()
+elseif(UNIX AND NOT APPLE AND NOT (${PX4_PLATFORM} MATCHES "qurt")) #TODO: add linux PX4 platform type
+	# Linux I2Cdev and SPIdev
 	list(APPEND SRCS_PLATFORM
 		posix/I2C.cpp
+		posix/SPI.cpp
 	)
 endif()
 
diff --git a/src/lib/drivers/device/posix/SPI.cpp b/src/lib/drivers/device/posix/SPI.cpp
new file mode 100644
index 0000000000..9c021d03e6
--- /dev/null
+++ b/src/lib/drivers/device/posix/SPI.cpp
@@ -0,0 +1,198 @@
+/****************************************************************************
+ *
+ *   Copyright (C) 2019 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file SPI.cpp
+ *
+ * Base class for devices connected via SPI.
+ *
+ */
+
+#include "SPI.hpp"
+
+#ifdef __PX4_LINUX
+
+#include <fcntl.h>
+#include <unistd.h>
+#include <sys/ioctl.h>
+#include <linux/types.h>
+#include <linux/spi/spidev.h>
+
+#include <px4_config.h>
+
+namespace device
+{
+
+SPI::SPI(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode, uint32_t frequency) :
+	CDev(name, devname),
+	_device(device),
+	_mode(mode),
+	_frequency(frequency)
+{
+	DEVICE_DEBUG("SPI::SPI name = %s devname = %s", name, devname);
+
+	// fill in _device_id fields for a SPI device
+	_device_id.devid_s.bus_type = DeviceBusType_SPI;
+	_device_id.devid_s.bus = bus;
+	_device_id.devid_s.address = (uint8_t)device;
+	// devtype needs to be filled in by the driver
+	_device_id.devid_s.devtype = 0;
+}
+
+SPI::~SPI()
+{
+	if (_fd >= 0) {
+		::close(_fd);
+		_fd = -1;
+	}
+}
+
+int
+SPI::init()
+{
+	int ret = OK;
+
+	// Open the actual SPI device
+	char dev_path[16];
+	snprintf(dev_path, sizeof(dev_path), "/dev/spidev%i.%i", get_device_bus(), PX4_SPI_DEV_ID(_device));
+	DEVICE_DEBUG("%s", dev_path);
+	_fd = ::open(dev_path, O_RDWR);
+
+	if (_fd < 0) {
+		PX4_ERR("could not open %s", dev_path);
+		return PX4_ERROR;
+	}
+
+	/* call the probe function to check whether the device is present */
+	ret = probe();
+
+	if (ret != OK) {
+		DEVICE_DEBUG("probe failed");
+		return ret;
+	}
+
+	/* do base class init, which will create the device node, etc. */
+	ret = CDev::init();
+
+	if (ret != OK) {
+		DEVICE_DEBUG("cdev init failed");
+		return ret;
+	}
+
+	/* tell the workd where we are */
+	DEVICE_LOG("on SPI bus %d at %d (%u KHz)", get_device_bus(), PX4_SPI_DEV_ID(_device), _frequency / 1000);
+
+	return PX4_OK;
+}
+
+int
+SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
+{
+	if ((send == nullptr) && (recv == nullptr)) {
+		return -EINVAL;
+	}
+
+	// set write mode of SPI
+	int result = ::ioctl(_fd, SPI_IOC_WR_MODE, &_mode);
+
+	if (result == -1) {
+		PX4_ERR("can’t set spi mode");
+		return PX4_ERROR;
+	}
+
+	spi_ioc_transfer spi_transfer[1] {}; // datastructures for linux spi interface
+
+	spi_transfer[0].tx_buf = (uint64_t)send;
+	spi_transfer[0].rx_buf = (uint64_t)recv;
+	spi_transfer[0].len = len;
+	spi_transfer[0].speed_hz = _frequency;
+	spi_transfer[0].bits_per_word = 8;
+	//spi_transfer[0].delay_usecs = 10;
+	spi_transfer[0].cs_change = true;
+
+	result = ::ioctl(_fd, SPI_IOC_MESSAGE(1), &spi_transfer);
+
+	if (result != (int)len) {
+		PX4_ERR("write failed. Reported %d bytes written (%s)", result, strerror(errno));
+		return -1;
+	}
+
+	return 0;
+}
+
+int
+SPI::transferhword(uint16_t *send, uint16_t *recv, unsigned len)
+{
+	if ((send == nullptr) && (recv == nullptr)) {
+		return -EINVAL;
+	}
+
+	// set write mode of SPI
+	int result = ::ioctl(_fd, SPI_IOC_WR_MODE, &_mode);
+
+	if (result == -1) {
+		PX4_ERR("can’t set spi mode");
+		return PX4_ERROR;
+	}
+
+	int bits = 16;
+	result = ::ioctl(_fd, SPI_IOC_WR_BITS_PER_WORD, &bits);
+
+	if (result == -1) {
+		PX4_ERR("can’t set 16 bit spi mode");
+		return PX4_ERROR;
+	}
+
+	spi_ioc_transfer spi_transfer[1] {}; // datastructures for linux spi interface
+
+	spi_transfer[0].tx_buf = (uint64_t)send;
+	spi_transfer[0].rx_buf = (uint64_t)recv;
+	spi_transfer[0].len = len * 2;
+	spi_transfer[0].speed_hz = _frequency;
+	//spi_transfer[0].bits_per_word = 8;
+	//spi_transfer[0].delay_usecs = 10;
+	spi_transfer[0].cs_change = true;
+
+	result = ::ioctl(_fd, SPI_IOC_MESSAGE(1), &spi_transfer);
+
+	if (result != (int)(len * 2)) {
+		PX4_ERR("write failed. Reported %d bytes written (%s)", result, strerror(errno));
+		return -1;
+	}
+
+	return 0;
+}
+
+} // namespace device
+
+#endif // __PX4_LINUX
diff --git a/src/lib/drivers/device/posix/SPI.hpp b/src/lib/drivers/device/posix/SPI.hpp
index cf9260a987..6ce5825fc4 100644
--- a/src/lib/drivers/device/posix/SPI.hpp
+++ b/src/lib/drivers/device/posix/SPI.hpp
@@ -1,6 +1,6 @@
 /****************************************************************************
  *
- *   Copyright (C) 2017 PX4 Development Team. All rights reserved.
+ *   Copyright (C) 2019 PX4 Development Team. All rights reserved.
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions
@@ -32,7 +32,7 @@
  ****************************************************************************/
 
 /**
- * @file spi.h
+ * @file SPI.hpp
  *
  * Base class for devices connected via SPI.
  */
@@ -40,13 +40,144 @@
 #ifndef _DEVICE_SPI_H
 #define _DEVICE_SPI_H
 
-#include "CDev.hpp"
+#include "../CDev.hpp"
+
+#ifdef __PX4_LINUX
+
+#include <fcntl.h>
+#include <unistd.h>
+#include <sys/ioctl.h>
+#include <linux/types.h>
+#include <linux/spi/spidev.h>
+
+enum spi_mode_e {
+	SPIDEV_MODE0 = SPI_MODE_0, /* CPOL=0 CHPHA=0 */
+	SPIDEV_MODE1 = SPI_MODE_1, /* CPOL=0 CHPHA=1 */
+	SPIDEV_MODE2 = SPI_MODE_2, /* CPOL=1 CHPHA=0 */
+	SPIDEV_MODE3 = SPI_MODE_3  /* CPOL=1 CHPHA=1 */
+};
 
 namespace device __EXPORT
 {
 
-// TODO: implement posix spi
+/**
+ * Abstract class for character device on SPI
+ */
+class __EXPORT SPI : public CDev
+{
+protected:
+	/**
+	 * Constructor
+	 *
+	 * @param name		Driver name
+	 * @param devname	Device node name
+	 * @param bus		SPI bus on which the device lives
+	 * @param device	Device handle (used by SPI_SELECT)
+	 * @param mode		SPI clock/data mode
+	 * @param frequency	SPI clock frequency
+	 */
+	SPI(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode, uint32_t frequency);
+	virtual ~SPI();
+
+	/**
+	 * Locking modes supported by the driver.
+	 */
+	enum LockMode {
+		LOCK_PREEMPTION,	/**< the default; lock against all forms of preemption. */
+		LOCK_THREADS,		/**< lock only against other threads, using SPI_LOCK */
+		LOCK_NONE		/**< perform no locking, only safe if the bus is entirely private */
+	};
+
+	virtual int	init();
+
+	/**
+	 * Check for the presence of the device on the bus.
+	 */
+	virtual int	probe() { return PX4_OK; }
+
+	/**
+	 * Perform a SPI transfer.
+	 *
+	 * If called from interrupt context, this interface does not lock
+	 * the bus and may interfere with non-interrupt-context callers.
+	 *
+	 * Clients in a mixed interrupt/non-interrupt configuration must
+	 * ensure appropriate interlocking.
+	 *
+	 * At least one of send or recv must be non-null.
+	 *
+	 * @param send		Bytes to send to the device, or nullptr if
+	 *			no data is to be sent.
+	 * @param recv		Buffer for receiving bytes from the device,
+	 *			or nullptr if no bytes are to be received.
+	 * @param len		Number of bytes to transfer.
+	 * @return		OK if the exchange was successful, -errno
+	 *			otherwise.
+	 */
+	int		transfer(uint8_t *send, uint8_t *recv, unsigned len);
+
+	/**
+	 * Perform a SPI 16 bit transfer.
+	 *
+	 * If called from interrupt context, this interface does not lock
+	 * the bus and may interfere with non-interrupt-context callers.
+	 *
+	 * Clients in a mixed interrupt/non-interrupt configuration must
+	 * ensure appropriate interlocking.
+	 *
+	 * At least one of send or recv must be non-null.
+	 *
+	 * @param send		Words to send to the device, or nullptr if
+	 *			no data is to be sent.
+	 * @param recv		Words for receiving bytes from the device,
+	 *			or nullptr if no bytes are to be received.
+	 * @param len		Number of words to transfer.
+	 * @return		OK if the exchange was successful, -errno
+	 *			otherwise.
+	 */
+	int		transferhword(uint16_t *send, uint16_t *recv, unsigned len);
+
+	/**
+	 * Set the SPI bus frequency
+	 * This is used to change frequency on the fly. Some sensors
+	 * (such as the MPU6000) need a lower frequency for setup
+	 * registers and can handle higher frequency for sensor
+	 * value registers
+	 *
+	 * @param frequency	Frequency to set (Hz)
+	 */
+	void		set_frequency(uint32_t frequency) { _frequency = frequency; }
+	uint32_t		get_frequency() { return _frequency; }
+
+	/**
+	 * Set the SPI bus locking mode
+	 *
+	 * This set the SPI locking mode. For devices competing with NuttX SPI
+	 * drivers on a bus the right lock mode is LOCK_THREADS.
+	 *
+	 * @param mode	Locking mode
+	 */
+	void		set_lockmode(enum LockMode mode) {}
+
+private:
+	int 			_fd{-1};
+
+	uint32_t		_device;
+	enum spi_mode_e		_mode;
+	uint32_t		_frequency;
+
+	/* this class does not allow copying */
+	SPI(const SPI &);
+	SPI operator=(const SPI &);
+
+protected:
+
+	bool	external() { return px4_spi_bus_external(get_device_bus()); }
+
+};
 
 } // namespace device
 
+#endif // __PX4_LINUX
+
 #endif /* _DEVICE_SPI_H */
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 14cf01836b..becf7becad 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -128,8 +128,9 @@ const struct {
 	{"controllib",		controllib_test_main,	0},
 #ifndef __PX4_NUTTX
 	{"mavlink",		mavlink_tests_main,	0},
-#endif
+#else
 	{"sf0x",		sf0x_tests_main,	0},
+#endif
 	{"uorb",		uorb_tests_main,	0},
 
 	{NULL,			NULL, 		0}
-- 
GitLab