Skip to content

Commit

Permalink
mpu9250 allow a 2nd internal spi instance and remove px4fmu-v4 fake e…
Browse files Browse the repository at this point in the history
…xternal (#9386)
  • Loading branch information
dagar authored May 4, 2018
1 parent 92f1528 commit 6b94ef1
Show file tree
Hide file tree
Showing 6 changed files with 47 additions and 87 deletions.
3 changes: 1 addition & 2 deletions src/drivers/boards/px4fmu-v4/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,6 @@
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_RAMTRON 2
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_RAMTRON
#define PX4_SPI_BUS_EXT 1

/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
Expand All @@ -148,7 +147,7 @@
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 11)
#define PX4_SPIDEV_BMI055_ACC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 12)
#define PX4_SPIDEV_BMI055_GYR PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 13)
#define PX4_SPIDEV_EXT_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 14)
#define PX4_SPIDEV_MPU2 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 14)

/* onboard MS5611 and FRAM are both on bus SPI2
* spi_dev_e:SPIDEV_FLASH has the value 2 and is used in the NuttX ramtron driver
Expand Down
4 changes: 1 addition & 3 deletions src/drivers/boards/px4fmu-v4/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool s
case PX4_SPIDEV_ICM_20602:
case PX4_SPIDEV_ICM_20608:
case PX4_SPIDEV_BMI055_ACC:
case PX4_SPIDEV_EXT_MPU:
case PX4_SPIDEV_MPU2:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN2, 1);
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN15, !selected);
Expand Down Expand Up @@ -237,6 +237,4 @@ __EXPORT void board_spi_reset(int ms)
stm32_configgpio(GPIO_SPI1_SCK);
stm32_configgpio(GPIO_SPI1_MISO);
stm32_configgpio(GPIO_SPI1_MOSI);


}
41 changes: 30 additions & 11 deletions src/drivers/imu/mpu9250/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,11 @@
#define MPU_DEVICE_PATH_ACCEL "/dev/mpu9250_accel"
#define MPU_DEVICE_PATH_GYRO "/dev/mpu9250_gyro"
#define MPU_DEVICE_PATH_MAG "/dev/mpu9250_mag"

#define MPU_DEVICE_PATH_ACCEL_1 "/dev/mpu9250_accel1"
#define MPU_DEVICE_PATH_GYRO_1 "/dev/mpu9250_gyro1"
#define MPU_DEVICE_PATH_MAG_1 "/dev/mpu9250_mag1"

#define MPU_DEVICE_PATH_ACCEL_EXT "/dev/mpu9250_accel_ext"
#define MPU_DEVICE_PATH_GYRO_EXT "/dev/mpu9250_gyro_ext"
#define MPU_DEVICE_PATH_MAG_EXT "/dev/mpu9250_mag_ext"
Expand All @@ -87,6 +92,7 @@ enum MPU9250_BUS {
MPU9250_BUS_I2C_INTERNAL,
MPU9250_BUS_I2C_EXTERNAL,
MPU9250_BUS_SPI_INTERNAL,
MPU9250_BUS_SPI_INTERNAL2,
MPU9250_BUS_SPI_EXTERNAL
};

Expand All @@ -109,21 +115,25 @@ struct mpu9250_bus_option {
MPU9250_constructor interface_constructor;
bool magpassthrough;
uint8_t busnum;
uint32_t address;
MPU9250 *dev;
} bus_options[] = {
#if defined (USE_I2C)
# if defined(PX4_I2C_BUS_ONBOARD)
{ MPU9250_BUS_I2C_INTERNAL, MPU_DEVICE_PATH_ACCEL, MPU_DEVICE_PATH_GYRO, MPU_DEVICE_PATH_MAG, &MPU9250_I2C_interface, false, PX4_I2C_BUS_ONBOARD, NULL },
{ MPU9250_BUS_I2C_INTERNAL, MPU_DEVICE_PATH_ACCEL, MPU_DEVICE_PATH_GYRO, MPU_DEVICE_PATH_MAG, &MPU9250_I2C_interface, false, PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_MPU9250, NULL },
# endif
# if defined(PX4_I2C_BUS_EXPANSION)
{ MPU9250_BUS_I2C_EXTERNAL, MPU_DEVICE_PATH_ACCEL_EXT, MPU_DEVICE_PATH_GYRO_EXT, MPU_DEVICE_PATH_MAG_EXT, &MPU9250_I2C_interface, false, PX4_I2C_BUS_EXPANSION, NULL },
{ MPU9250_BUS_I2C_EXTERNAL, MPU_DEVICE_PATH_ACCEL_EXT, MPU_DEVICE_PATH_GYRO_EXT, MPU_DEVICE_PATH_MAG_EXT, &MPU9250_I2C_interface, false, PX4_I2C_BUS_EXPANSION, PX4_I2C_OBDEV_MPU9250, NULL },
# endif
#endif
#ifdef PX4_SPIDEV_MPU
{ MPU9250_BUS_SPI_INTERNAL, MPU_DEVICE_PATH_ACCEL, MPU_DEVICE_PATH_GYRO, MPU_DEVICE_PATH_MAG, &MPU9250_SPI_interface, true, PX4_SPI_BUS_SENSORS, NULL },
{ MPU9250_BUS_SPI_INTERNAL, MPU_DEVICE_PATH_ACCEL, MPU_DEVICE_PATH_GYRO, MPU_DEVICE_PATH_MAG, &MPU9250_SPI_interface, true, PX4_SPI_BUS_SENSORS, PX4_SPIDEV_MPU, NULL },
#endif
#ifdef PX4_SPIDEV_MPU2
{ MPU9250_BUS_SPI_INTERNAL2, MPU_DEVICE_PATH_ACCEL_1, MPU_DEVICE_PATH_GYRO_1, MPU_DEVICE_PATH_MAG_1, &MPU9250_SPI_interface, true, PX4_SPI_BUS_SENSORS, PX4_SPIDEV_MPU2, NULL },
#endif
#if defined(PX4_SPI_BUS_EXT)
{ MPU9250_BUS_SPI_EXTERNAL, MPU_DEVICE_PATH_ACCEL_EXT, MPU_DEVICE_PATH_GYRO_EXT, MPU_DEVICE_PATH_MAG_EXT, &MPU9250_SPI_interface, true, PX4_SPI_BUS_EXT, NULL },
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_MPU)
{ MPU9250_BUS_SPI_EXTERNAL, MPU_DEVICE_PATH_ACCEL_EXT, MPU_DEVICE_PATH_GYRO_EXT, MPU_DEVICE_PATH_MAG_EXT, &MPU9250_SPI_interface, true, PX4_SPI_BUS_EXT, PX4_SPIDEV_EXT_MPU, NULL },
#endif
};

Expand Down Expand Up @@ -169,7 +179,7 @@ start_bus(struct mpu9250_bus_option &bus, enum Rotation rotation, bool external)
return false;
}

device::Device *interface = bus.interface_constructor(bus.busnum, external);
device::Device *interface = bus.interface_constructor(bus.busnum, bus.address, external);

if (interface == nullptr) {
warnx("no device on bus %u", (unsigned)bus.busid);
Expand Down Expand Up @@ -453,10 +463,15 @@ testerror(enum MPU9250_BUS busid)
void
usage()
{
warnx("missing command: try 'start', 'info', 'test', 'stop',\n'reset', 'regdump', 'testerror'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
PX4_INFO("missing command: try 'start', 'info', 'test', 'stop',\n'reset', 'regdump', 'testerror'");
PX4_INFO("options:");
PX4_INFO(" -X (i2c external bus)");
PX4_INFO(" -I (i2c internal bus)");
PX4_INFO(" -s (spi internal bus)");
PX4_INFO(" -S (spi external bus)");
PX4_INFO(" -t (spi internal bus, 2nd instance)");
PX4_INFO(" -R rotation");

}

} // namespace
Expand All @@ -470,7 +485,7 @@ mpu9250_main(int argc, char *argv[])
enum Rotation rotation = ROTATION_NONE;

/* jump over start/off/etc and look at options first */
while ((ch = getopt(argc, argv, "XISsR:")) != EOF) {
while ((ch = getopt(argc, argv, "XISstR:")) != EOF) {
switch (ch) {
case 'X':
busid = MPU9250_BUS_I2C_EXTERNAL;
Expand All @@ -488,6 +503,10 @@ mpu9250_main(int argc, char *argv[])
busid = MPU9250_BUS_SPI_INTERNAL;
break;

case 't':
busid = MPU9250_BUS_SPI_INTERNAL2;
break;

case 'R':
rotation = (enum Rotation)atoi(optarg);
break;
Expand Down
9 changes: 3 additions & 6 deletions src/drivers/imu/mpu9250/mpu9250.h
Original file line number Diff line number Diff line change
Expand Up @@ -231,14 +231,11 @@ struct MPUReport {
# define MPU9250_LOW_SPEED_OP(r) MPU9250_REG((r))

/* interface factories */
extern device::Device *MPU9250_SPI_interface(int bus, bool external_bus);
extern device::Device *MPU9250_I2C_interface(int bus, bool external_bus);
extern device::Device *MPU9250_SPI_interface(int bus, uint32_t cs, bool external_bus);
extern device::Device *MPU9250_I2C_interface(int bus, uint32_t address, bool external_bus);
extern int MPU9250_probe(device::Device *dev, int device_type);

typedef device::Device *(*MPU9250_constructor)(int, bool);



typedef device::Device *(*MPU9250_constructor)(int, uint32_t, bool);

class MPU9250_mag;
class MPU9250_gyro;
Expand Down
30 changes: 8 additions & 22 deletions src/drivers/imu/mpu9250/mpu9250_i2c.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,15 +61,14 @@

#ifdef USE_I2C

device::Device *MPU9250_I2C_interface(int bus, bool external_bus);
device::Device *MPU9250_I2C_interface(int bus, uint32_t address, bool external_bus);

class MPU9250_I2C : public device::I2C
{
public:
MPU9250_I2C(int bus);
virtual ~MPU9250_I2C();
MPU9250_I2C(int bus, uint32_t address);
virtual ~MPU9250_I2C() = default;

virtual int init();
virtual int read(unsigned address, void *data, unsigned count);
virtual int write(unsigned address, void *data, unsigned count);

Expand All @@ -80,34 +79,22 @@ class MPU9250_I2C : public device::I2C

};


device::Device *
MPU9250_I2C_interface(int bus, bool external_bus)
MPU9250_I2C_interface(int bus, uint32_t address, bool external_bus)
{
return new MPU9250_I2C(bus);
return new MPU9250_I2C(bus, address);
}

MPU9250_I2C::MPU9250_I2C(int bus) :
I2C("MPU9250_I2C", nullptr, bus, PX4_I2C_OBDEV_MPU9250, 400000)
MPU9250_I2C::MPU9250_I2C(int bus, uint32_t address) :
I2C("MPU9250_I2C", nullptr, bus, address, 400000)
{
_device_id.devid_s.devtype = DRV_ACC_DEVTYPE_MPU9250;
}

MPU9250_I2C::~MPU9250_I2C()
{
}

int
MPU9250_I2C::init()
{
/* this will call probe() */
return I2C::init();
}

int
MPU9250_I2C::ioctl(unsigned operation, unsigned &arg)
{
int ret;
int ret = PX4_ERROR;

switch (operation) {

Expand Down Expand Up @@ -155,7 +142,6 @@ MPU9250_I2C::read(unsigned reg_speed, void *data, unsigned count)
return transfer(&cmd, 1, &((uint8_t *)data)[offset], count);
}


int
MPU9250_I2C::probe()
{
Expand Down
47 changes: 4 additions & 43 deletions src/drivers/imu/mpu9250/mpu9250_spi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,15 +64,6 @@
#define DIR_READ 0x80
#define DIR_WRITE 0x00


#if PX4_SPIDEV_MPU
#ifdef PX4_SPI_BUS_EXT
#define EXTERNAL_BUS PX4_SPI_BUS_EXT
#else
#define EXTERNAL_BUS 0
#endif


/*
* The MPU9250 can only handle high SPI bus speeds of 20Mhz on the sensor and
* interrupt status registers. All other registers have a maximum 1MHz
Expand All @@ -86,16 +77,15 @@
#define MPU9250_HIGH_SPI_BUS_SPEED 20*1000*1000


device::Device *MPU9250_SPI_interface(int bus, bool external_bus);
device::Device *MPU9250_SPI_interface(int bus, uint32_t cs, bool external_bus);


class MPU9250_SPI : public device::SPI
{
public:
MPU9250_SPI(int bus, uint32_t device);
virtual ~MPU9250_SPI();
virtual ~MPU9250_SPI() = default;

virtual int init();
virtual int read(unsigned address, void *data, unsigned count);
virtual int write(unsigned address, void *data, unsigned count);

Expand All @@ -111,24 +101,17 @@ class MPU9250_SPI : public device::SPI
};

device::Device *
MPU9250_SPI_interface(int bus, bool external_bus)
MPU9250_SPI_interface(int bus, uint32_t cs, bool external_bus)
{
uint32_t cs = SPIDEV_NONE(0);
device::Device *interface = nullptr;

if (external_bus) {
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_MPU)
cs = PX4_SPIDEV_EXT_MPU;
#else
#if !(defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_MPU))
errx(0, "External SPI not available");
#endif

} else {
cs = PX4_SPIDEV_MPU;
}

if (cs != SPIDEV_NONE(0)) {

interface = new MPU9250_SPI(bus, cs);
}

Expand All @@ -141,25 +124,6 @@ MPU9250_SPI::MPU9250_SPI(int bus, uint32_t device) :
_device_id.devid_s.devtype = DRV_ACC_DEVTYPE_MPU9250;
}

MPU9250_SPI::~MPU9250_SPI()
{
}

int
MPU9250_SPI::init()
{
int ret;

ret = SPI::init();

if (ret != OK) {
DEVICE_DEBUG("SPI init failed");
return -EIO;
}

return OK;
}

int
MPU9250_SPI::ioctl(unsigned operation, unsigned &arg)
{
Expand Down Expand Up @@ -198,7 +162,6 @@ MPU9250_SPI::set_bus_frequency(unsigned &reg_speed)
reg_speed = MPU9250_REG(reg_speed);
}


int
MPU9250_SPI::write(unsigned reg_speed, void *data, unsigned count)
{
Expand Down Expand Up @@ -287,5 +250,3 @@ MPU9250_SPI::probe()

return ret;
}

#endif // PX4_SPIDEV_MPU

0 comments on commit 6b94ef1

Please sign in to comment.