pixhawk px4 spi设备驱动

此篇blog是以nuttx官网介绍为出发点,先分析如何初始化的,再分析如何读取传感器数据的,最后对比了字符型设备操作和spi驱动的实现方式的差别(如有错误还请指正)

6.字符型设备

所有的结构体和API都在Firmware/Nuttx/nuttx/include/nuttx/fs/fs.h

每个字符设备驱动程序必须实现struct file_operations的实例

struct file_operations{
int open(FAR struct file *filep);
int close(FAR struct file *filep);
ssize_t read(FAR struct file *filep, FAR char *buffer, size_t buflen);
ssize_t write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
off_t seek(FAR struct file *filep, off_t offset, int whence);
int ioctl(FAR struct file *filep, int cmd, unsigned long arg);
int poll(FAR struct file *filep, struct pollfd *fds, bool setup);
}

调用int register_driver(const char *path, const struct file_operations*fops, mode_t mode, void *priv)(Firmware/Nuttx/nuttx/fs/fs_registerdrivers.c)之后就可以使用用户接口 driver operations 包括 open()close()read()write(), etc.

SPI Device Drivers

所有的spi的设备驱动和API接口都在Firmware/Nuttx/nuttx/include/nuttx/spi/spi.h

每个串口设备驱动程序必须实现struct spi_ops_s的实例

struct spi_ops_s
{
#ifndef CONFIG_SPI_OWNBUS
  int      (*lock)(FAR struct spi_dev_s *dev, bool lock);
#endif
  void     (*select)(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
                     bool selected);
  uint32_t (*setfrequency)(FAR struct spi_dev_s *dev, uint32_t frequency);
  void     (*setmode)(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
  void     (*setbits)(FAR struct spi_dev_s *dev, int nbits);
  uint8_t  (*status)(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
#ifdef CONFIG_SPI_CMDDATA
  int      (*cmddata)(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#endif
  uint16_t (*send)(FAR struct spi_dev_s *dev, uint16_t wd);
#ifdef CONFIG_SPI_EXCHANGE
  void     (*exchange)(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
                       FAR void *rxbuffer, size_t nwords);
#else
  void     (*sndblock)(FAR struct spi_dev_s *dev, FAR const void *buffer,
                       size_t nwords);
  void     (*recvblock)(FAR struct spi_dev_s *dev, FAR void *buffer,
                        size_t nwords);
#endif
  int     (*registercallback)(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
                              void *arg);
};

例子:Firmware/Nuttx/nuttx/arch/arm/src/stm32/stm32_spi.c

#ifdef CONFIG_STM32_SPI1
static const struct spi_ops_s g_sp1iops =
{
#ifndef CONFIG_SPI_OWNBUS
  .lock              = spi_lock,
#endif
  .select            = stm32_spi1select,
  .setfrequency      = spi_setfrequency,
  .setmode           = spi_setmode,
  .setbits           = spi_setbits,
  .status            = stm32_spi1status,
#ifdef CONFIG_SPI_CMDDATA
  .cmddata           = stm32_spi1cmddata,
#endif
  .send              = spi_send,
#ifdef CONFIG_SPI_EXCHANGE
  .exchange          = spi_exchange,
#else
  .sndblock          = spi_sndblock,
  .recvblock         = spi_recvblock,
#endif
  .registercallback  = 0,
};

spi_ops_s结构体的成员是指向函数的指针

/************************************************************************************
 * Name: spi_setfrequency
 *
 * Description:
 *   Set the SPI frequency.
 *
 * Input Parameters:
 *   dev -       Device-specific state data
 *   frequency - The SPI frequency requested
 *
 * Returned Value:
 *   Returns the actual frequency selected
 *
 ************************************************************************************/
static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
{
  FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev;
  uint16_t setbits;
  uint32_t actual;
  /* Limit to max possible (if STM32_SPI_CLK_MAX is defined in board.h) */
  if (frequency > STM32_SPI_CLK_MAX)
    {
      frequency = STM32_SPI_CLK_MAX;
    }
  /* Has the frequency changed? */
#ifndef CONFIG_SPI_OWNBUS
  if (frequency != priv->frequency)
    {
#endif
      /* Choices are limited by PCLK frequency with a set of divisors */
      if (frequency >= priv->spiclock >> 1)
        {
          /* More than fPCLK/2.  This is as fast as we can go */
          setbits = SPI_CR1_FPCLCKd2; /* 000: fPCLK/2 */
          actual = priv->spiclock >> 1;
        }
      else if (frequency >= priv->spiclock >> 2)
        {
          /* Between fPCLCK/2 and fPCLCK/4, pick the slower */
          setbits = SPI_CR1_FPCLCKd4; /* 001: fPCLK/4 */
          actual = priv->spiclock >> 2;
       }
      else if (frequency >= priv->spiclock >> 3)
        {
          /* Between fPCLCK/4 and fPCLCK/8, pick the slower */
          setbits = SPI_CR1_FPCLCKd8; /* 010: fPCLK/8 */
          actual = priv->spiclock >> 3;
        }
      else if (frequency >= priv->spiclock >> 4)
        {
          /* Between fPCLCK/8 and fPCLCK/16, pick the slower */
          setbits = SPI_CR1_FPCLCKd16; /* 011: fPCLK/16 */
          actual = priv->spiclock >> 4;
        }
      else if (frequency >= priv->spiclock >> 5)
        {
          /* Between fPCLCK/16 and fPCLCK/32, pick the slower */
          setbits = SPI_CR1_FPCLCKd32; /* 100: fPCLK/32 */
          actual = priv->spiclock >> 5;
        }
      else if (frequency >= priv->spiclock >> 6)
        {
          /* Between fPCLCK/32 and fPCLCK/64, pick the slower */
          setbits = SPI_CR1_FPCLCKd64; /*  101: fPCLK/64 */
          actual = priv->spiclock >> 6;
        }
      else if (frequency >= priv->spiclock >> 7)
        {
          /* Between fPCLCK/64 and fPCLCK/128, pick the slower */
          setbits = SPI_CR1_FPCLCKd128; /* 110: fPCLK/128 */
          actual = priv->spiclock >> 7;
        }
      else
        {
          /* Less than fPCLK/128.  This is as slow as we can go */
          setbits = SPI_CR1_FPCLCKd256; /* 111: fPCLK/256 */
          actual = priv->spiclock >> 8;
        }
      spi_modifycr1(priv, 0, SPI_CR1_SPE);
      spi_modifycr1(priv, setbits, SPI_CR1_BR_MASK);
      spi_modifycr1(priv, SPI_CR1_SPE, 0);
      /* Save the frequency selection so that subsequent reconfigurations will be
       * faster.
       */
      spivdbg("Frequency %d->%d\n", frequency, actual);
#ifndef CONFIG_SPI_OWNBUS
      priv->frequency = frequency;
      priv->actual    = actual;
    }
  return priv->actual;
#else
  return actual;
#endif
}

static struct stm32_spidev_sg_spi1dev结构体会把staticconst struct spi_ops_s g_sp1iops包含在内

注意下面结构体中含有.spidev   = { &g_sp1iops }

static struct stm32_spidev_s g_spi1dev =
{
  .spidev   = { &g_sp1iops },
  .spibase  = STM32_SPI1_BASE,
  .spiclock = STM32_PCLK2_FREQUENCY,
#ifdef CONFIG_STM32_SPI_INTERRUPTS
  .spiirq   = STM32_IRQ_SPI1,
#endif
#ifdef CONFIG_STM32_SPI_DMA
  .rxch     = DMACHAN_SPI1_RX,
  .txch     = DMACHAN_SPI1_TX,
#endif
};
#endif

这样g_spi1dev就可以代表一个spi端口了

然后利用up_spiinitialize就可以初始化spi端口了

/************************************************************************************
 * Name: up_spiinitialize
 *
 * Description:
 *   Initialize the selected SPI port
 *
 * Input Parameter:
 *   Port number (for hardware that has mutiple SPI interfaces)
 *
 * Returned Value:
 *   Valid SPI device structure reference on succcess; a NULL on failure
 *
 ************************************************************************************/
FAR struct spi_dev_s *up_spiinitialize(int port)
{
  FAR struct stm32_spidev_s *priv = NULL;
  irqstate_t flags = irqsave();
#ifdef CONFIG_STM32_SPI1
  if (port == 1)
    {
      /* Select SPI1 */
      priv = &g_spi1dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI1 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI1_SCK);
          stm32_configgpio(GPIO_SPI1_MISO);
          stm32_configgpio(GPIO_SPI1_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif
#ifdef CONFIG_STM32_SPI2
  if (port == 2)
    {
      /* Select SPI2 */
      priv = &g_spi2dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI2 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI2_SCK);
          stm32_configgpio(GPIO_SPI2_MISO);
          stm32_configgpio(GPIO_SPI2_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif
#ifdef CONFIG_STM32_SPI3
  if (port == 3)
    {
      /* Select SPI3 */
      priv = &g_spi3dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI3 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI3_SCK);
          stm32_configgpio(GPIO_SPI3_MISO);
          stm32_configgpio(GPIO_SPI3_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif
#ifdef CONFIG_STM32_SPI4
  if (port == 4)
    {
      /* Select SPI4 */
      priv = &g_spi4dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI4 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI4_SCK);
          stm32_configgpio(GPIO_SPI4_MISO);
          stm32_configgpio(GPIO_SPI4_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif
#ifdef CONFIG_STM32_SPI5
  if (port == 5)
    {
      /* Select SPI5 */
      priv = &g_spi5dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI5 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI5_SCK);
          stm32_configgpio(GPIO_SPI5_MISO);
          stm32_configgpio(GPIO_SPI5_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif
#ifdef CONFIG_STM32_SPI6
  if (port == 6)
    {
      /* Select SPI6 */
      priv = &g_spi6dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI6 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI6_SCK);
          stm32_configgpio(GPIO_SPI6_MISO);
          stm32_configgpio(GPIO_SPI6_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif
    {
      spidbg("ERROR: Unsupported SPI port: %d\n", port);
      return NULL;
    }
  irqrestore(flags);
  return (FAR struct spi_dev_s *)priv;
}
#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 || CONFIG_STM32_SPI3 || CONFIG_STM32_SPI4 || CONFIG_STM32_SPI5 || CONFIG_STM32_SPI6 */

此时看谁调用了up_spiinitialize

Firmware/src/platforms/px4_micro_hal.h

#  define px4_spibus_initialize(port_1based)      up_spiinitialize(port_1based)

看到这里应该很熟悉了吧,px4的mpu6000读取会初始化mpu6000然后再初始化mpu6000的函数里会调用spi的初始化,spi的初始化函数中就有px4_spibus_initialize(port_1based)

我们还是往上层搜,看调用关系

接下来在Firmware/src/drivers/device/spi.cpp中SPI::init()函数里调用px4_spibus_initialize(port_1based)

int SPI::init()
{
	int ret = OK;
	/* attach to the spi bus */
	if (_dev == nullptr) {
		_dev = px4_spibus_initialize(_bus);
	}
	if (_dev == nullptr) {
		DEVICE_DEBUG("failed to init SPI");
		ret = -ENOENT;
		goto out;
	}
	/* 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();
	if (ret != OK) {
		DEVICE_DEBUG("probe failed");
		goto out;
	}
	/* do base class init, which will create the device node, etc. */
	ret = CDev::init();
	if (ret != OK) {
		DEVICE_DEBUG("cdev init failed");
		goto out;
	}
	/* tell the workd where we are */
	DEVICE_LOG("on SPI bus %d at %d (%u KHz)", _bus, _device, _frequency / 1000);
out:
	return ret;
}

然后只要使用了spi的传感器都会调用SPI::init(),比如mpu6000

int MPU6000::init()
{
	int ret;
	/* do SPI init (and probe) first */
	ret = SPI::init();
	/* if probe/setup failed, bail now */
	if (ret != OK) {
		DEVICE_DEBUG("SPI setup failed");
		return ret;
	}
	/* allocate basic report buffers */
	_accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report));
	if (_accel_reports == nullptr) {
		goto out;
	}
	_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
	if (_gyro_reports == nullptr) {
		goto out;
	}
	if (reset() != OK) {
		goto out;
	}
	/* Initialize offsets and scales */
	_accel_scale.x_offset = 0;
	_accel_scale.x_scale  = 1.0f;
	_accel_scale.y_offset = 0;
	_accel_scale.y_scale  = 1.0f;
	_accel_scale.z_offset = 0;
	_accel_scale.z_scale  = 1.0f;
	_gyro_scale.x_offset = 0;
	_gyro_scale.x_scale  = 1.0f;
	_gyro_scale.y_offset = 0;
	_gyro_scale.y_scale  = 1.0f;
	_gyro_scale.z_offset = 0;
	_gyro_scale.z_scale  = 1.0f;
	/* do CDev init for the gyro device node, keep it optional */
	ret = _gyro->init();
	/* if probe/setup failed, bail now */
	if (ret != OK) {
		DEVICE_DEBUG("gyro init failed");
		return ret;
	}
	_accel_class_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH);
	measure();
	/* advertise sensor topic, measure manually to initialize valid report */
	struct accel_report arp;
	_accel_reports->get(&arp);
	/* measurement will have generated a report, publish */
	_accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp,
					   &_accel_orb_class_instance, (is_external()) ? ORB_PRIO_MAX : ORB_PRIO_HIGH);
	if (_accel_topic == nullptr) {
		warnx("ADVERT FAIL");
	}
	/* advertise sensor topic, measure manually to initialize valid report */
	struct gyro_report grp;
	_gyro_reports->get(&grp);
	_gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp,
			     &_gyro->_gyro_orb_class_instance, (is_external()) ? ORB_PRIO_MAX : ORB_PRIO_HIGH);
	if (_gyro->_gyro_topic == nullptr) {
		warnx("ADVERT FAIL");
	}
out:
	return ret;
}

这样初始化的这条线就走通了,主要过程就是:每个spi端口都会有structspi_ops_s的实例,spi_ops_s结构体的成员是指向函数的指针,比如spi1的端口staticconststructspi_ops_s g_sp1iopsstaticstructstm32_spidev_s g_spi1dev结构体会把staticconststructspi_ops_s g_sp1iops包含在内,这样g_spi1dev就可以代表一个spi端口了;然后利用up_spiinitialize就可以初始化spi端口了;之后使用spi端口的传感器在初始化中都会调用SPI::init(),从而调用up_spiinitialize

可以发现spi的操作没有register(),

SPI驱动程序通常不由用户代码直接访问,但通常绑定到另一个更高级别的设备驱动程序(例如mpu6000),绑定的顺序是:从硬件特定的SPI设备驱动程序获取struct spi_dev_s的实例,将该实例提供给较高级别设备驱动程序的初始化方法。

那么nuttx是如何利用spi读取传感器的数据的?以mpu6000为例

根据MPU6000的读取过程,读取函数是

void MPU6000::measure()
{
	if (_in_factory_test) {
		// don't publish any data while in factory test mode
		return;
	}
	if (hrt_absolute_time() < _reset_wait) {
		// we're waiting for a reset to complete
		return;
	}
	struct MPUReport mpu_report;
	struct Report {
		int16_t		accel_x;
		int16_t		accel_y;
		int16_t		accel_z;
		int16_t		temp;
		int16_t		gyro_x;
		int16_t		gyro_y;
		int16_t		gyro_z;
	} report;
	/* start measuring */
	perf_begin(_sample_perf);
	/*
	 * Fetch the full set of measurements from the MPU6000 in one pass.
	 */
	mpu_report.cmd = DIR_READ | MPUREG_INT_STATUS;
	// sensor transfer at high clock speed
	set_frequency(MPU6000_HIGH_BUS_SPEED);
	if (OK != transfer((uint8_t *)&mpu_report, ((uint8_t *)&mpu_report), sizeof(mpu_report))) {
		return;
	}
	check_registers();
	/*
	   see if this is duplicate accelerometer data. Note that we
	   can't use the data ready interrupt status bit in the status
	   register as that also goes high on new gyro data, and when
	   we run with BITS_DLPF_CFG_256HZ_NOLPF2 the gyro is being
	   sampled at 8kHz, so we would incorrectly think we have new
	   data when we are in fact getting duplicate accelerometer data.
	*/
	if (!_got_duplicate && memcmp(&mpu_report.accel_x[0], &_last_accel[0], 6) == 0) {
		// it isn't new data - wait for next timer
		perf_end(_sample_perf);
		perf_count(_duplicates);
		_got_duplicate = true;
		return;
	}
	memcpy(&_last_accel[0], &mpu_report.accel_x[0], 6);
	_got_duplicate = false;
	/*
	 * Convert from big to little endian
	 */
	report.accel_x = int16_t_from_bytes(mpu_report.accel_x);
	report.accel_y = int16_t_from_bytes(mpu_report.accel_y);
	report.accel_z = int16_t_from_bytes(mpu_report.accel_z);
	report.temp = int16_t_from_bytes(mpu_report.temp);
	report.gyro_x = int16_t_from_bytes(mpu_report.gyro_x);
	report.gyro_y = int16_t_from_bytes(mpu_report.gyro_y);
	report.gyro_z = int16_t_from_bytes(mpu_report.gyro_z);
	if (report.accel_x == 0 &&
	    report.accel_y == 0 &&
	    report.accel_z == 0 &&
	    report.temp == 0 &&
	    report.gyro_x == 0 &&
	    report.gyro_y == 0 &&
	    report.gyro_z == 0) {
		// all zero data - probably a SPI bus error
		perf_count(_bad_transfers);
		perf_end(_sample_perf);
		// note that we don't call reset() here as a reset()
		// costs 20ms with interrupts disabled. That means if
		// the mpu6k does go bad it would cause a FMU failure,
		// regardless of whether another sensor is available,
		return;
	}
	perf_count(_good_transfers);
	if (_register_wait != 0) {
		// we are waiting for some good transfers before using
		// the sensor again. We still increment
		// _good_transfers, but don't return any data yet
		_register_wait--;
		return;
	}
	/*
	 * Swap axes and negate y
	 */
	int16_t accel_xt = report.accel_y;
	int16_t accel_yt = ((report.accel_x == -32768) ? 32767 : -report.accel_x);
	int16_t gyro_xt = report.gyro_y;
	int16_t gyro_yt = ((report.gyro_x == -32768) ? 32767 : -report.gyro_x);
	/*
	 * Apply the swap
	 */
	report.accel_x = accel_xt;
	report.accel_y = accel_yt;
	report.gyro_x = gyro_xt;
	report.gyro_y = gyro_yt;
	/*
	 * Report buffers.
	 */
	accel_report		arb;
	gyro_report		grb;
	/*
	 * Adjust and scale results to m/s^2.
	 */
	grb.timestamp = arb.timestamp = hrt_absolute_time();
	// report the error count as the sum of the number of bad
	// transfers and bad register reads. This allows the higher
	// level code to decide if it should use this sensor based on
	// whether it has had failures
	grb.error_count = arb.error_count = perf_event_count(_bad_transfers) + perf_event_count(_bad_registers);
	/*
	 * 1) Scale raw value to SI units using scaling from datasheet.
	 * 2) Subtract static offset (in SI units)
	 * 3) Scale the statically calibrated values with a linear
	 *    dynamically obtained factor
	 *
	 * Note: the static sensor offset is the number the sensor outputs
	 * 	 at a nominally 'zero' input. Therefore the offset has to
	 * 	 be subtracted.
	 *
	 *	 Example: A gyro outputs a value of 74 at zero angular rate
	 *	 	  the offset is 74 from the origin and subtracting
	 *		  74 from all measurements centers them around zero.
	 */
	/* NOTE: Axes have been swapped to match the board a few lines above. */
	arb.x_raw = report.accel_x;
	arb.y_raw = report.accel_y;
	arb.z_raw = report.accel_z;
	float xraw_f = report.accel_x;
	float yraw_f = report.accel_y;
	float zraw_f = report.accel_z;
	// apply user specified rotation
	rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
	float x_in_new = ((xraw_f * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
	float y_in_new = ((yraw_f * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
	float z_in_new = ((zraw_f * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
	arb.x = _accel_filter_x.apply(x_in_new);
	arb.y = _accel_filter_y.apply(y_in_new);
	arb.z = _accel_filter_z.apply(z_in_new);
	math::Vector<3> aval(x_in_new, y_in_new, z_in_new);
	math::Vector<3> aval_integrated;
	bool accel_notify = _accel_int.put(arb.timestamp, aval, aval_integrated, arb.integral_dt);
	arb.x_integral = aval_integrated(0);
	arb.y_integral = aval_integrated(1);
	arb.z_integral = aval_integrated(2);
	arb.scaling = _accel_range_scale;
	arb.range_m_s2 = _accel_range_m_s2;
	if (is_icm_device()) { // if it is an ICM20608
		_last_temperature = (report.temp) / 326.8f + 25.0f;
	} else { // If it is an MPU6000
		_last_temperature = (report.temp) / 361.0f + 35.0f;
	}
	arb.temperature_raw = report.temp;
	arb.temperature = _last_temperature;
	grb.x_raw = report.gyro_x;
	grb.y_raw = report.gyro_y;
	grb.z_raw = report.gyro_z;
	xraw_f = report.gyro_x;
	yraw_f = report.gyro_y;
	zraw_f = report.gyro_z;
	// apply user specified rotation
	rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
	float x_gyro_in_new = ((xraw_f * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
	float y_gyro_in_new = ((yraw_f * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
	float z_gyro_in_new = ((zraw_f * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
	grb.x = _gyro_filter_x.apply(x_gyro_in_new);
	grb.y = _gyro_filter_y.apply(y_gyro_in_new);
	grb.z = _gyro_filter_z.apply(z_gyro_in_new);
	math::Vector<3> gval(x_gyro_in_new, y_gyro_in_new, z_gyro_in_new);
	math::Vector<3> gval_integrated;
	bool gyro_notify = _gyro_int.put(arb.timestamp, gval, gval_integrated, grb.integral_dt);
	grb.x_integral = gval_integrated(0);
	grb.y_integral = gval_integrated(1);
	grb.z_integral = gval_integrated(2);
	grb.scaling = _gyro_range_scale;
	grb.range_rad_s = _gyro_range_rad_s;
	grb.temperature_raw = report.temp;
	grb.temperature = _last_temperature;
	_accel_reports->force(&arb);
	_gyro_reports->force(&grb);
	/* notify anyone waiting for data */
	if (accel_notify) {
		poll_notify(POLLIN);
	}
	if (gyro_notify) {
		_gyro->parent_poll_notify();
	}
	if (accel_notify && !(_pub_blocked)) {
		/* log the time of this report */
		perf_begin(_controller_latency_perf);
		/* publish it */
		orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb);
	}
	if (gyro_notify && !(_pub_blocked)) {
		/* publish it */
		orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb);
	}
	/* stop measuring */
	perf_end(_sample_perf);
}

读取就是通过if (OK != transfer((uint8_t *)&mpu_report,((uint8_t *)&mpu_report),sizeof(mpu_report)))来完成的

进入transfer()

int SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
	int result;
	if ((send == nullptr) && (recv == nullptr)) {
		return -EINVAL;
	}
	LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode;
	/* lock the bus as required */
	switch (mode) {
	default:
	case LOCK_PREEMPTION: {
			irqstate_t state = px4_enter_critical_section();
			result = _transfer(send, recv, len);
			px4_leave_critical_section(state);
		}
		break;
	case LOCK_THREADS:
		SPI_LOCK(_dev, true);
		result = _transfer(send, recv, len);
		SPI_LOCK(_dev, false);
		break;
	case LOCK_NONE:
		result = _transfer(send, recv, len);
		break;
	}
	return result;
}
再进入result = _transfer(send, recv, len);
int SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
	SPI_SETFREQUENCY(_dev, _frequency);
	SPI_SETMODE(_dev, _mode);
	SPI_SETBITS(_dev, 8);
	SPI_SELECT(_dev, _device, true);
	/* do the transfer */
	SPI_EXCHANGE(_dev, send, recv, len);
	/* and clean up */
	SPI_SELECT(_dev, _device, false);
	return OK;
}

这个函数里面的语句都是宏定义,在Firmware/Nuttx/nuttx/include/nuttx/spi.h中

#define SPI_SETFREQUENCY(d,f) ((d)->ops->setfrequency(d,f))
#define SPI_SETMODE(d,m) \
  do { if ((d)->ops->setmode) (d)->ops->setmode(d,m); } while (0)
#define SPI_SETBITS(d,b) \
  do { if ((d)->ops->setbits) (d)->ops->setbits(d,b); } while (0)
#define SPI_SELECT(d,id,s) ((d)->ops->select(d,id,s))
#ifdef CONFIG_SPI_EXCHANGE
#  define SPI_EXCHANGE(d,t,r,l) ((d)->ops->exchange(d,t,r,l))
#endif

接着跟,就可以跟到最前面提到的“每个串口设备驱动程序必须实现struct spi_ops_s实例”,struct spi_ops_s这个结构体了

struct spi_ops_s
{
#ifndef CONFIG_SPI_OWNBUS
  int      (*lock)(FAR struct spi_dev_s *dev, bool lock);
#endif
  void     (*select)(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
                     bool selected);
  uint32_t (*setfrequency)(FAR struct spi_dev_s *dev, uint32_t frequency);
  void     (*setmode)(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
  void     (*setbits)(FAR struct spi_dev_s *dev, int nbits);
  uint8_t  (*status)(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
#ifdef CONFIG_SPI_CMDDATA
  int      (*cmddata)(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#endif
  uint16_t (*send)(FAR struct spi_dev_s *dev, uint16_t wd);
#ifdef CONFIG_SPI_EXCHANGE
  void     (*exchange)(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
                       FAR void *rxbuffer, size_t nwords);
#else
  void     (*sndblock)(FAR struct spi_dev_s *dev, FAR const void *buffer,
                       size_t nwords);
  void     (*recvblock)(FAR struct spi_dev_s *dev, FAR void *buffer,
                        size_t nwords);
#endif
  int     (*registercallback)(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
                              void *arg);
};

这是一个指向函数的结构体,而在此处是联系到

Firmware/Nuttx/nuttx/arch/arm/src/stm32/stm32_spi.c

#ifdef CONFIG_STM32_SPI1
static const struct spi_ops_s g_sp1iops =
{
#ifndef CONFIG_SPI_OWNBUS
  .lock              = spi_lock,
#endif
  .select            = stm32_spi1select,
  .setfrequency      = spi_setfrequency,
  .setmode           = spi_setmode,
  .setbits           = spi_setbits,
  .status            = stm32_spi1status,
#ifdef CONFIG_SPI_CMDDATA
  .cmddata           = stm32_spi1cmddata,
#endif
  .send              = spi_send,
#ifdef CONFIG_SPI_EXCHANGE
  .exchange          = spi_exchange,
#else
  .sndblock          = spi_sndblock,
  .recvblock         = spi_recvblock,
#endif
  .registercallback  = 0,
};
……(还包含CONFIG_STM32_SPI2/ CONFIG_STM32_SPI3等)

这样就可以利用

SPI_EXCHANGE(_dev, send, recv, len);

>> 

void    (*exchange)(FARstruct spi_dev_s *dev, FARconst void *txbuffer,

                       FAR void *rxbuffer, size_tnwords);

>> 

.exchange          = spi_exchange,

>> 

/************************************************************************************
 * Name: spi_exchange (no DMA).  aka spi_exchange_nodma
 *
 * Description:
 *   Exchange a block of data on SPI without using DMA
 *
 * Input Parameters:
 *   dev      - Device-specific state data
 *   txbuffer - A pointer to the buffer of data to be sent
 *   rxbuffer - A pointer to a buffer in which to receive data
 *   nwords   - the length of data to be exchaned in units of words.
 *              The wordsize is determined by the number of bits-per-word
 *              selected for the SPI interface.  If nbits <= 8, the data is
 *              packed into uint8_t's; if nbits >8, the data is packed into uint16_t's
 *
 * Returned Value:
 *   None
 *
 ************************************************************************************/
#if !defined(CONFIG_STM32_SPI_DMA) || defined(CONFIG_STM32_DMACAPABLE)
#if !defined(CONFIG_STM32_SPI_DMA)
static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
                         FAR void *rxbuffer, size_t nwords)
#else
static void spi_exchange_nodma(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
                               FAR void *rxbuffer, size_t nwords)
#endif
{
  FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev;
  DEBUGASSERT(priv && priv->spibase);
  spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords);
  /* 8- or 16-bit mode? */
  if (spi_16bitmode(priv))
    {
      /* 16-bit mode */
      const uint16_t *src  = (const uint16_t*)txbuffer;;
            uint16_t *dest = (uint16_t*)rxbuffer;
            uint16_t  word;
      while (nwords-- > 0)
        {
          /* Get the next word to write.  Is there a source buffer? */
          if (src)
            {
              word = *src++;
            }
          else
          {
              word = 0xffff;
          }
          /* Exchange one word */
          word = spi_send(dev, word);
          /* Is there a buffer to receive the return value? */
          if (dest)
            {
              *dest++ = word;
            }
        }
    }
  else
    {
      /* 8-bit mode */
      const uint8_t *src  = (const uint8_t*)txbuffer;;
            uint8_t *dest = (uint8_t*)rxbuffer;
            uint8_t  word;
      while (nwords-- > 0)
        {
          /* Get the next word to write.  Is there a source buffer? */
          if (src)
            {
              word = *src++;
            }
          else
          {
              word = 0xff;
          }
          /* Exchange one word */
          word = (uint8_t)spi_send(dev, (uint16_t)word);
          /* Is there a buffer to receive the return value? */
          if (dest)
            {
              *dest++ = word;
            }
        }
    }
}
#endif /* !CONFIG_STM32_SPI_DMA || CONFIG_STM32_DMACAPABLE */
/*************************************************************************
 * Name: spi_exchange (with DMA capability)
 *
 * Description:
 *   Exchange a block of data on SPI using DMA
 *
 * Input Parameters:
 *   dev      - Device-specific state data
 *   txbuffer - A pointer to the buffer of data to be sent
 *   rxbuffer - A pointer to a buffer in which to receive data
 *   nwords   - the length of data to be exchanged in units of words.
 *              The wordsize is determined by the number of bits-per-word
 *              selected for the SPI interface.  If nbits <= 8, the data is
 *              packed into uint8_t's; if nbits >8, the data is packed into uint16_t's
 *
 * Returned Value:
 *   None
 *
 ************************************************************************************/
#ifdef CONFIG_STM32_SPI_DMA
static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
                         FAR void *rxbuffer, size_t nwords)
{
#ifdef CONFIG_STM32_DMACAPABLE
  if ((txbuffer && !stm32_dmacapable((uint32_t)txbuffer)) ||
      (rxbuffer && !stm32_dmacapable((uint32_t)rxbuffer)))
    {
      /* Unsupported memory region, fall back to non-DMA method. */
      spi_exchange_nodma(dev, txbuffer, rxbuffer, nwords);
    }
  else
#endif
    {
      FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev;
      static uint16_t rxdummy = 0xffff;
      static const uint16_t txdummy = 0xffff;
      spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords);
      DEBUGASSERT(priv && priv->spibase);
      /* Setup DMAs */
      spi_dmarxsetup(priv, rxbuffer, &rxdummy, nwords);
      spi_dmatxsetup(priv, txbuffer, &txdummy, nwords);
      /* Start the DMAs */
      spi_dmarxstart(priv);
      spi_dmatxstart(priv);
      /* Then wait for each to complete */
      spi_dmarxwait(priv);
      spi_dmatxwait(priv);
    }
}
#endif /* CONFIG_STM32_SPI_DMA */

到此,mpu6000读取完成了,但是还有个问题struct spi_ops_s为什么就能对应到Firmware/Nuttx/nuttx/arch/arm/src/stm32/stm32_spi.c

#ifdef CONFIG_STM32_SPI1
static const struct spi_ops_s g_sp1iops =
{
#ifndef CONFIG_SPI_OWNBUS
  .lock              = spi_lock,
#endif
  .select            = stm32_spi1select,
  .setfrequency      = spi_setfrequency,
  .setmode           = spi_setmode,
  .setbits           = spi_setbits,
  .status            = stm32_spi1status,
#ifdef CONFIG_SPI_CMDDATA
  .cmddata           = stm32_spi1cmddata,
#endif
  .send              = spi_send,
#ifdef CONFIG_SPI_EXCHANGE
  .exchange          = spi_exchange,
#else
  .sndblock          = spi_sndblock,
  .recvblock         = spi_recvblock,
#endif
  .registercallback  = 0,
};
……(还包含CONFIG_STM32_SPI2/CONFIG_STM32_SPI3等)

d                   (d)->ops->exchange(d,t,r,l)

_dev             SPI_EXCHANGE(_dev, send, recv, len)//Firmware/src/drivers/device/spi.cpp

_dev =px4_spibus_initialize(_bus);//Firmware/src/drivers/device/spi.cpp

_bus          

*g_dev_ptr = new MPU6000(PX4_SPI_BUS_SENSORS,path_accel, path_gyro, cs, rotation, device_type);                                //mpu6000.cpp

MPU6000::MPU6000(int bus,const char *path_accel,const char *path_gyro,spi_dev_e device,enum Rotation rotation, int device_type) :

SPI("MPU6000", path_accel,bus,device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED)

SPI::SPI(const char *name,
	 const char *devname,
	 int bus,
	 enum spi_dev_e device,
	 enum spi_mode_e mode,
	 uint32_t frequency,
	 int irq) :
	// base class
	CDev(name, devname, irq),
	// public
	// protected
	locking_mode(LOCK_PREEMPTION),
	// private
	_device(device),
	_mode(mode),
	_frequency(frequency),
	_dev(nullptr),
	_bus(bus)
{
	// 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;
}

d>>_dev>>_bus bus>>PX4_SPI_BUS_SENSORS,这样传递的

#define PX4_SPI_BUS_SENSORS	1             //Firmware/src/drivers/px4fmu-v2/board_config.h
#define PX4_SPI_BUS_RAMTRON	2
#define PX4_SPI_BUS_EXT		4
#define PX4_SPI_BUS_BARO	PX4_SPI_BUS_SENSORS

这样传递就可以发现是那个spi端口吗?就能对应到哪个端口?

当然,再看到前面

此时看谁调用了up_spiinitialize

Firmware/src/platforms/px4_micro_hal.h

#define px4_spibus_initialize(port_1based)       up_spiinitialize(port_1based)

看到这里应该很熟悉了吧,px4mpu6000读取会初始化mpu6000然后再初始化mpu6000的函数里会调用spi的初始化,spi的初始化函数中就有px4_spibus_initialize(port_1based)

up_spiinitialize()就是初始化端口的,这样调用的SPI_EXCHANGE就可以和端口对应起来了

另外,不知各位发现没

Firmware/Nuttx/nuttx/arch/arm/src/stm32/stm32_spi.c

#ifdef CONFIG_STM32_SPI1
static const struct spi_ops_s g_sp1iops =
{
#ifndef CONFIG_SPI_OWNBUS
  .lock              = spi_lock,
#endif
  .select            = stm32_spi1select,
  .setfrequency      = spi_setfrequency,
  .setmode           = spi_setmode,
  .setbits           = spi_setbits,
  .status            = stm32_spi1status,
#ifdef CONFIG_SPI_CMDDATA
  .cmddata           = stm32_spi1cmddata,
#endif
  .send              = spi_send,
#ifdef CONFIG_SPI_EXCHANGE
  .exchange          = spi_exchange,
#else
  .sndblock          = spi_sndblock,
  .recvblock         = spi_recvblock,
#endif
  .registercallback  = 0,
};
……(还包含CONFIG_STM32_SPI2/ CONFIG_STM32_SPI3等)
/************************************************************************************
 * Name: up_spiinitialize
 *
 * Description:
 *   Initialize the selected SPI port
 *
 * Input Parameter:
 *   Port number (for hardware that has mutiple SPI interfaces)
 *
 * Returned Value:
 *   Valid SPI device structure reference on succcess; a NULL on failure
 *
 ************************************************************************************/
FAR struct spi_dev_s *up_spiinitialize(int port)
{
  FAR struct stm32_spidev_s *priv = NULL;
  irqstate_t flags = irqsave();
#ifdef CONFIG_STM32_SPI1
  if (port == 1)
    {
      /* Select SPI1 */
      priv = &g_spi1dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI1 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI1_SCK);
          stm32_configgpio(GPIO_SPI1_MISO);
          stm32_configgpio(GPIO_SPI1_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif
#ifdef CONFIG_STM32_SPI2
  if (port == 2)
    {
      /* Select SPI2 */
      priv = &g_spi2dev;
      /* Only configure if the port is not already configured */
      if ((spi_getreg(priv, STM32_SPI_CR1_OFFSET) & SPI_CR1_SPE) == 0)
        {
          /* Configure SPI2 pins: SCK, MISO, and MOSI */
          stm32_configgpio(GPIO_SPI2_SCK);
          stm32_configgpio(GPIO_SPI2_MISO);
          stm32_configgpio(GPIO_SPI2_MOSI);
          /* Set up default configuration: Master, 8-bit, etc. */
          spi_portinitialize(priv);
        }
    }
  else
#endif

这2段程序都有#ifdef CONFIG_STM32_SPI1,判断CONFIG_STM32_SPI1的值,如果CONFIG_STM32_SPI1为1则会运行之后的程序,若为0则不会运行之后的程序,那么哪里会给CONFIG_STM32_SPI1赋值呢?

看到Firmware/nuttx_configs/px4fmu-v2/nsh/defconfig里面

CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI2=y
# CONFIG_STM32_SPI3 is not set
CONFIG_STM32_SPI4=y
# CONFIG_STM32_SPI5 is not set
# CONFIG_STM32_SPI6 is not set

这里定义了,也就是要用哪个端口就应该在这里使能哪个端口

还可以发现上面的使能几个端口正好和board_config.h定义的几个端口一致

#define PX4_SPI_BUS_SENSORS	1             //Firmware/src/drivers/px4fmu-v2/board_config.h
#define PX4_SPI_BUS_RAMTRON	2
#define PX4_SPI_BUS_EXT		4
#define PX4_SPI_BUS_BARO	PX4_SPI_BUS_SENSORS

总结一下:用spi_ops_sspi_getreg结构体可以代表spi端口,up_spiinitialize里面调用了spi_getreg结构体就可以初始化某个spi端口了,之后具体的传感器驱动都会调用up_spiinitialize,这样初始化就完成了。

传感器驱动会调用int SPI::_transfer(uint8_t*send, uint8_t *recv, unsignedlen),这个里面的程序都能对应到在Firmware/Nuttx/nuttx/include/nuttx/spi.h中{#defineSPI_SETFREQUENCY(d,f)((d)->ops->setfrequency(d,f))……}进而利用spi_ops_s结构体对应到相应的spi底层驱动函数

可以发现,mpu6000并没有用字符型设备操作,即read/write等,而是直接利用(d)->ops->setfrequency(d,f)spi_ops_s直接操作底层驱动。当然,也可以用read/write函数

可以查看mpu6000的test函数

void test(bool external_bus)
{
	const char *path_accel = external_bus ? MPU_DEVICE_PATH_ACCEL_EXT : MPU_DEVICE_PATH_ACCEL;
	const char *path_gyro  = external_bus ? MPU_DEVICE_PATH_GYRO_EXT : MPU_DEVICE_PATH_GYRO;
	accel_report a_report;
	gyro_report g_report;
	ssize_t sz;
	/* get the driver */
	int fd = open(path_accel, O_RDONLY);
	if (fd < 0)
		err(1, "%s open failed (try 'mpu6000 start')",
		    path_accel);
	/* get the driver */
	int fd_gyro = open(path_gyro, O_RDONLY);
	if (fd_gyro < 0) {
		err(1, "%s open failed", path_gyro);
	}
	/* reset to manual polling */
	if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0) {
		err(1, "reset to manual polling");
	}
	/* do a simple demand read */
	sz = read(fd, &a_report, sizeof(a_report));
	if (sz != sizeof(a_report)) {
		warnx("ret: %d, expected: %d", sz, sizeof(a_report));
		err(1, "immediate acc read failed");
	}
	warnx("single read");
	warnx("time:     %lld", a_report.timestamp);
	warnx("acc  x:  \t%8.4f\tm/s^2", (double)a_report.x);
	warnx("acc  y:  \t%8.4f\tm/s^2", (double)a_report.y);
	warnx("acc  z:  \t%8.4f\tm/s^2", (double)a_report.z);
	warnx("acc  x:  \t%d\traw 0x%0x", (short)a_report.x_raw, (unsigned short)a_report.x_raw);
	warnx("acc  y:  \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
	warnx("acc  z:  \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
	warnx("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
	      (double)(a_report.range_m_s2 / MPU6000_ONE_G));
	/* do a simple demand read */
	sz = read(fd_gyro, &g_report, sizeof(g_report));
	if (sz != sizeof(g_report)) {
		warnx("ret: %d, expected: %d", sz, sizeof(g_report));
		err(1, "immediate gyro read failed");
	}
	warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x);
	warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y);
	warnx("gyro z: \t% 9.5f\trad/s", (double)g_report.z);
	warnx("gyro x: \t%d\traw", (int)g_report.x_raw);
	warnx("gyro y: \t%d\traw", (int)g_report.y_raw);
	warnx("gyro z: \t%d\traw", (int)g_report.z_raw);
	warnx("gyro range: %8.4f rad/s (%d deg/s)", (double)g_report.range_rad_s,
	      (int)((g_report.range_rad_s / M_PI_F) * 180.0f + 0.5f));
	warnx("temp:  \t%8.4f\tdeg celsius", (double)a_report.temperature);
	warnx("temp:  \t%d\traw 0x%0x", (short)a_report.temperature_raw, (unsigned short)a_report.temperature_raw);
	/* reset to default polling */
	if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
		err(1, "reset to default polling");
	}
	close(fd);
	close(fd_gyro);
	/* XXX add poll-rate tests here too */
	reset(external_bus);
	errx(0, "PASS");
}

非常明显的open>>read的操作

还有一个疑问:mpu6000直接采用一个结构体对应到底层驱动函数,那到底需不需要注册呢?

注册的目的是为了将节点注册到系统(节点都会有read/write字符型设备的操作,具体的节点的read/write都对应到具体的驱动函数),并且与路径相对应,之后就可以使用路径访问到节点,进而通过路径知道驱动的位置,若直接采用底层的驱动而不用字符型设备操作,那么猜测不用注册设备。用字符型设备的操作有一个好处,就是只要注册了,都可以通过open该设备进行read/write了,而使用指向函数的指针结构体对应到具体的驱动函数,则需要理清楚他是如何对应的,如果那里没有对应好,那么读取或者写入都难以实现。

_gyro_class_instance = register_class_devname(GYRO_BASE_DEVICE_PATH);
_accel_class_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH);
int CDev::register_class_devname(const char *class_devname)
{
	if (class_devname == nullptr) {
		return -EINVAL;
	}
	int class_instance = 0;
	int ret = -ENOSPC;
	while (class_instance < 4) {
		char name[32];
		snprintf(name, sizeof(name), "%s%d", class_devname, class_instance);
		ret = register_driver(name, &fops, 0666, (void *)this);
		if (ret == OK) { break; }
		class_instance++;
	}
	if (class_instance == 4) {
		return ret;
	}
	return class_instance;
}
int register_driver(FAR const char *path, FAR const struct file_operations *fops,
                    mode_t mode, FAR void *priv)
{
  FAR struct inode *node;
  int ret;
  /* Insert a dummy node -- we need to hold the inode semaphore because we
   * will have a momentarily bad structure.
   */
  inode_semtake();
  ret = inode_reserve(path, &node);
  if (ret >= 0)
    {
      /* We have it, now populate it with driver specific information. */
      INODE_SET_DRIVER(node);
      node->u.i_ops   = fops;
#ifdef CONFIG_FILE_MODE
      node->i_mode    = mode;
#endif
      node->i_private = priv;
      ret             = OK;
    }
  inode_semgive();
  return ret;
}
 
如果您觉得此文对您的发展有用,请随意打赏。  

您的鼓励将是笔者书写高质量文章的最大动力^_^!!


  • 7
    点赞
  • 25
    收藏
    觉得还不错? 一键收藏
  • 6
    评论
评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值