forked from Archive/PX4-Autopilot
PX4 SPI default to thread locking mode
This commit is contained in:
parent
7d248e0f45
commit
5d813224c8
|
@ -124,14 +124,7 @@ MS5611_SPI::MS5611_SPI(uint8_t bus, uint32_t device, ms5611::prom_u &prom_buf) :
|
|||
int
|
||||
MS5611_SPI::init()
|
||||
{
|
||||
int ret;
|
||||
|
||||
#if defined(PX4_SPI_BUS_RAMTRON) && \
|
||||
(PX4_SPI_BUS_BARO == PX4_SPI_BUS_RAMTRON)
|
||||
SPI::set_lockmode(LOCK_THREADS);
|
||||
#endif
|
||||
|
||||
ret = SPI::init();
|
||||
int ret = SPI::init();
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_DEBUG("SPI init failed");
|
||||
|
|
|
@ -341,9 +341,6 @@ PMW3901::init()
|
|||
_yaw_rotation = (enum Rotation)val;
|
||||
}
|
||||
|
||||
/* For devices competing with NuttX SPI drivers on a bus (Crazyflie SD Card expansion board) */
|
||||
SPI::set_lockmode(LOCK_THREADS);
|
||||
|
||||
/* do SPI init (and probe) first */
|
||||
if (SPI::init() != OK) {
|
||||
goto out;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2012-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
|
||||
|
@ -57,18 +57,8 @@
|
|||
namespace device
|
||||
{
|
||||
|
||||
SPI::SPI(const char *name,
|
||||
const char *devname,
|
||||
int bus,
|
||||
uint32_t device,
|
||||
enum spi_mode_e mode,
|
||||
uint32_t frequency) :
|
||||
// base class
|
||||
SPI::SPI(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode, uint32_t frequency) :
|
||||
CDev(name, devname),
|
||||
// public
|
||||
// protected
|
||||
locking_mode(LOCK_PREEMPTION),
|
||||
// private
|
||||
_device(device),
|
||||
_mode(mode),
|
||||
_frequency(frequency),
|
||||
|
@ -90,15 +80,12 @@ SPI::~SPI()
|
|||
int
|
||||
SPI::init()
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
/* attach to the spi bus */
|
||||
if (_dev == nullptr) {
|
||||
int bus = get_device_bus();
|
||||
|
||||
if (!board_has_bus(BOARD_SPI_BUS, bus)) {
|
||||
ret = -ENOENT;
|
||||
goto out;
|
||||
return -ENOENT;
|
||||
}
|
||||
|
||||
_dev = px4_spibus_initialize(bus);
|
||||
|
@ -106,19 +93,18 @@ SPI::init()
|
|||
|
||||
if (_dev == nullptr) {
|
||||
DEVICE_DEBUG("failed to init SPI");
|
||||
ret = -ENOENT;
|
||||
goto out;
|
||||
return -ENOENT;
|
||||
}
|
||||
|
||||
/* deselect device to ensure high to low transition of pin select */
|
||||
SPI_SELECT(_dev, _device, false);
|
||||
|
||||
/* call the probe function to check whether the device is present */
|
||||
ret = probe();
|
||||
int ret = probe();
|
||||
|
||||
if (ret != OK) {
|
||||
DEVICE_DEBUG("probe failed");
|
||||
goto out;
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* do base class init, which will create the device node, etc. */
|
||||
|
@ -126,14 +112,13 @@ SPI::init()
|
|||
|
||||
if (ret != OK) {
|
||||
DEVICE_DEBUG("cdev init failed");
|
||||
goto out;
|
||||
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);
|
||||
|
||||
out:
|
||||
return ret;
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int
|
||||
|
@ -145,7 +130,7 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode;
|
||||
LockMode mode = up_interrupt_context() ? LOCK_NONE : _locking_mode;
|
||||
|
||||
/* lock the bus as required */
|
||||
switch (mode) {
|
||||
|
@ -185,7 +170,7 @@ SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
|
|||
/* and clean up */
|
||||
SPI_SELECT(_dev, _device, false);
|
||||
|
||||
return OK;
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int
|
||||
|
@ -197,7 +182,7 @@ SPI::transferhword(uint16_t *send, uint16_t *recv, unsigned len)
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode;
|
||||
LockMode mode = up_interrupt_context() ? LOCK_NONE : _locking_mode;
|
||||
|
||||
/* lock the bus as required */
|
||||
switch (mode) {
|
||||
|
@ -228,7 +213,7 @@ SPI::_transferhword(uint16_t *send, uint16_t *recv, unsigned len)
|
|||
{
|
||||
SPI_SETFREQUENCY(_dev, _frequency);
|
||||
SPI_SETMODE(_dev, _mode);
|
||||
SPI_SETBITS(_dev, 16); /* 16 bit transfer */
|
||||
SPI_SETBITS(_dev, 16); /* 16 bit transfer */
|
||||
SPI_SELECT(_dev, _device, true);
|
||||
|
||||
/* do the transfer */
|
||||
|
@ -237,7 +222,7 @@ SPI::_transferhword(uint16_t *send, uint16_t *recv, unsigned len)
|
|||
/* and clean up */
|
||||
SPI_SELECT(_dev, _device, false);
|
||||
|
||||
return OK;
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
} // namespace device
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file spi.h
|
||||
* @file SPI.hpp
|
||||
*
|
||||
* Base class for devices connected via SPI.
|
||||
*/
|
||||
|
@ -61,12 +61,7 @@ protected:
|
|||
* @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);
|
||||
SPI(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode, uint32_t frequency);
|
||||
virtual ~SPI();
|
||||
|
||||
/**
|
||||
|
@ -137,6 +132,7 @@ protected:
|
|||
* @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
|
||||
|
@ -146,16 +142,16 @@ protected:
|
|||
*
|
||||
* @param mode Locking mode
|
||||
*/
|
||||
void set_lockmode(enum LockMode mode) { locking_mode = mode; }
|
||||
|
||||
LockMode locking_mode; /**< selected locking mode */
|
||||
void set_lockmode(enum LockMode mode) { _locking_mode = mode; }
|
||||
|
||||
private:
|
||||
uint32_t _device;
|
||||
uint32_t _device;
|
||||
enum spi_mode_e _mode;
|
||||
uint32_t _frequency;
|
||||
struct spi_dev_s *_dev;
|
||||
|
||||
LockMode _locking_mode{LOCK_THREADS}; /**< selected locking mode */
|
||||
|
||||
/* this class does not allow copying */
|
||||
SPI(const SPI &);
|
||||
SPI operator=(const SPI &);
|
||||
|
|
|
@ -80,8 +80,6 @@ SPI::~SPI()
|
|||
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));
|
||||
|
@ -94,7 +92,7 @@ SPI::init()
|
|||
}
|
||||
|
||||
/* call the probe function to check whether the device is present */
|
||||
ret = probe();
|
||||
int ret = probe();
|
||||
|
||||
if (ret != OK) {
|
||||
DEVICE_DEBUG("probe failed");
|
||||
|
|
|
@ -79,15 +79,6 @@ protected:
|
|||
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();
|
||||
|
||||
/**
|
||||
|
@ -147,17 +138,7 @@ protected:
|
|||
* @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) {}
|
||||
uint32_t get_frequency() { return _frequency; }
|
||||
|
||||
private:
|
||||
int _fd{-1};
|
||||
|
|
Loading…
Reference in New Issue