Browse Source

refactor mpu9250: use driver base class

sbg
Beat Küng 5 years ago committed by Daniel Agar
parent
commit
7626be0485
  1. 2
      boards/bitcraze/crazyflie/init/rc.board_sensors
  2. 2
      boards/mro/x21-777/init/rc.board_sensors
  3. 2
      boards/mro/x21/init/rc.board_sensors
  4. 10
      boards/px4/fmu-v2/init/rc.board_sensors
  5. 10
      boards/px4/fmu-v3/init/rc.board_sensors
  6. 17
      boards/px4/fmu-v4/init/rc.board_sensors
  7. 2
      boards/px4/fmu-v4pro/init/rc.board_sensors
  8. 6
      boards/uvify/core/init/rc.board_sensors
  9. 2
      posix-configs/bbblue/px4.config
  10. 2
      posix-configs/bbblue/px4_fw.config
  11. 2
      posix-configs/eagle/200qx/px4.config
  12. 2
      posix-configs/eagle/210qc/px4.config
  13. 2
      posix-configs/excelsior/px4.config
  14. 2
      posix-configs/ocpoc/px4.config
  15. 2
      posix-configs/rpi/px4.config
  16. 2
      posix-configs/rpi/px4_fw.config
  17. 2
      posix-configs/rpi/px4_test.config
  18. 10
      src/drivers/imu/mpu9250/AK8963_I2C.cpp
  19. 4
      src/drivers/imu/mpu9250/MPU9250_mag.h
  20. 22
      src/drivers/imu/mpu9250/mpu9250.cpp
  21. 31
      src/drivers/imu/mpu9250/mpu9250.h
  22. 10
      src/drivers/imu/mpu9250/mpu9250_i2c.cpp
  23. 244
      src/drivers/imu/mpu9250/mpu9250_main.cpp
  24. 12
      src/drivers/imu/mpu9250/mpu9250_spi.cpp

2
boards/bitcraze/crazyflie/init/rc.board_sensors

@ -6,7 +6,7 @@
adc start adc start
# Onboard I2C # Onboard I2C
mpu9250 -R 12 start mpu9250 -I -R 12 start
# I2C bypass of mpu # I2C bypass of mpu
lps25h -I start lps25h -I start

2
boards/mro/x21-777/init/rc.board_sensors

@ -16,7 +16,7 @@ mpu6000 -s -R 2 -T 20608 start
mpu6000 -s -R 2 -T 20602 start mpu6000 -s -R 2 -T 20602 start
# Internal SPI bus mpu9250 is rotated 90 deg yaw # Internal SPI bus mpu9250 is rotated 90 deg yaw
mpu9250 -R 2 start mpu9250 -s -R 2 start
# Possible external compasses # Possible external compasses
ist8310 -X start ist8310 -X start

2
boards/mro/x21/init/rc.board_sensors

@ -18,7 +18,7 @@ mpu6000 -s -R 2 -T 20608 start
mpu6000 -s -R 2 -T 20602 start mpu6000 -s -R 2 -T 20602 start
# Internal SPI bus mpu9250 is rotated 90 deg yaw # Internal SPI bus mpu9250 is rotated 90 deg yaw
mpu9250 -R 2 start mpu9250 -s -R 2 start
# Internal SPI # Internal SPI
ms5611 -s start ms5611 -s start

10
boards/px4/fmu-v2/init/rc.board_sensors

@ -37,8 +37,8 @@ then
set BOARD_FMUV3 20 set BOARD_FMUV3 20
else else
# Check for Pixhawk 2.1 cube # Check for Pixhawk 2.1 cube
# external MPU9250 is rotated 180 degrees yaw # (external) MPU9250 is rotated 180 degrees yaw
if mpu9250 -S -R 4 start if mpu9250 -s -R 4 start
then then
set BOARD_FMUV3 21 set BOARD_FMUV3 21
fi fi
@ -57,8 +57,8 @@ then
set BOARD_FMUV3 20 set BOARD_FMUV3 20
else else
# Check for Pixhack 3.1 # Check for Pixhack 3.1
# external MPU9250 is rotated 180 degrees yaw # (external) MPU9250 is rotated 180 degrees yaw
if mpu9250 -S -R 4 start if mpu9250 -s -R 4 start
then then
set BOARD_FMUV3 21 set BOARD_FMUV3 21
fi fi
@ -101,7 +101,7 @@ else
# V3 build hwtypecmp supports V2|V2M|V30 # V3 build hwtypecmp supports V2|V2M|V30
if ! ver hwtypecmp V2M if ! ver hwtypecmp V2M
then then
mpu9250 start mpu9250 -s start
# else: On the PixhawkMini the mpu9250 has been disabled due to HW errata # else: On the PixhawkMini the mpu9250 has been disabled due to HW errata
fi fi

10
boards/px4/fmu-v3/init/rc.board_sensors

@ -38,8 +38,8 @@ then
set BOARD_FMUV3 20 set BOARD_FMUV3 20
else else
# Check for Pixhawk 2.1 cube # Check for Pixhawk 2.1 cube
# external MPU9250 is rotated 180 degrees yaw # (external) MPU9250 is rotated 180 degrees yaw
if mpu9250 -S -R 4 start if mpu9250 -s -R 4 start
then then
set BOARD_FMUV3 21 set BOARD_FMUV3 21
fi fi
@ -58,8 +58,8 @@ then
set BOARD_FMUV3 20 set BOARD_FMUV3 20
else else
# Check for Pixhack 3.1 # Check for Pixhack 3.1
# external MPU9250 is rotated 180 degrees yaw # (external) MPU9250 is rotated 180 degrees yaw
if mpu9250 -S -R 4 start if mpu9250 -s -R 4 start
then then
set BOARD_FMUV3 21 set BOARD_FMUV3 21
fi fi
@ -109,7 +109,7 @@ else
# V3 build hwtypecmp supports V2|V2M|V30 # V3 build hwtypecmp supports V2|V2M|V30
if ! ver hwtypecmp V2M if ! ver hwtypecmp V2M
then then
mpu9250 start mpu9250 -s start
# else: On the PixhawkMini the mpu9250 has been disabled due to HW errata # else: On the PixhawkMini the mpu9250 has been disabled due to HW errata
fi fi

17
boards/px4/fmu-v4/init/rc.board_sensors

@ -24,13 +24,6 @@ rm3100 start
# Internal SPI # Internal SPI
ms5611 -s start ms5611 -s start
# For Teal One airframe
if param compare SYS_AUTOSTART 4250
then
mpu9250 -s -R 14 start
mpu9250 -t -R 14 start
fi
# hmc5883 internal SPI bus is rotated 90 deg yaw # hmc5883 internal SPI bus is rotated 90 deg yaw
if ! hmc5883 -T -S -R 2 start if ! hmc5883 -T -S -R 2 start
then then
@ -49,5 +42,11 @@ then
icm20608g -R 8 start icm20608g -R 8 start
fi fi
# mpu9250 internal SPI bus mpu9250 is rotated 90 deg yaw # For Teal One airframe
mpu9250 -R 2 start if param compare SYS_AUTOSTART 4250
then
mpu9250 -s -R 14 start
else
# mpu9250 internal SPI bus mpu9250 is rotated 90 deg yaw
mpu9250 -s -R 2 start
fi

2
boards/px4/fmu-v4pro/init/rc.board_sensors

@ -14,7 +14,7 @@ icm20608g -R 8 start
icm20602 -s -R 8 start icm20602 -s -R 8 start
# Internal SPI bus mpu9250 # Internal SPI bus mpu9250
mpu9250 -R 2 start mpu9250 -s -R 2 start
# Internal SPI bus # Internal SPI bus
lis3mdl -R 0 start lis3mdl -R 0 start

6
boards/uvify/core/init/rc.board_sensors

@ -18,7 +18,7 @@ then
rgbled_ncp5623c start -X -a 0x38 rgbled_ncp5623c start -X -a 0x38
#mpu6000 -s -R 4 -T 20608 start #mpu6000 -s -R 4 -T 20608 start
mpu9250 -R 4 start mpu9250 -s -R 4 start
# Default GNSS with LIS3MDL magnetometer with external i2c. # Default GNSS with LIS3MDL magnetometer with external i2c.
lis3mdl -R 2 -X start lis3mdl -R 2 -X start
@ -27,7 +27,7 @@ fi
# Draco # Draco
if param compare SYS_AUTOSTART 4072 if param compare SYS_AUTOSTART 4072
then then
mpu9250 -R 2 start mpu9250 -s -R 2 start
fi fi
# IFO # IFO
@ -39,6 +39,6 @@ then
# IFO rgb LED # IFO rgb LED
pca9685 start pca9685 start
mpu9250 -R 2 start mpu9250 -s -R 2 start
lis3mdl -R 2 -X start lis3mdl -R 2 -X start
fi fi

2
posix-configs/bbblue/px4.config

@ -47,7 +47,7 @@ dataman start
bmp280 -I start bmp280 -I start
mpu9250 start mpu9250 -I start
# options: -R rotation # options: -R rotation
gps start -d /dev/ttyS2 -s -p ubx gps start -d /dev/ttyS2 -s -p ubx

2
posix-configs/bbblue/px4_fw.config

@ -47,7 +47,7 @@ dataman start
bmp280 -I start bmp280 -I start
mpu9250 start mpu9250 -I start
# options: -R rotation # options: -R rotation
gps start -d /dev/ttyS2 -s -p ubx gps start -d /dev/ttyS2 -s -p ubx

2
posix-configs/eagle/200qx/px4.config

@ -18,7 +18,7 @@ param set SENS_BOARD_ROT 0
sleep 1 sleep 1
mpu9250 start mpu9250 -s start
bmp280 -I start bmp280 -I start
gps start -d /dev/tty-4 gps start -d /dev/tty-4
rc_update start rc_update start

2
posix-configs/eagle/210qc/px4.config

@ -18,7 +18,7 @@ param set ATT_W_MAG 0.00
param set SENS_BOARD_ROT 0 param set SENS_BOARD_ROT 0
sleep 1 sleep 1
mpu9250 start mpu9250 -s start
bmp280 -I start bmp280 -I start
gps start -d /dev/tty-4 gps start -d /dev/tty-4
rc_update start rc_update start

2
posix-configs/excelsior/px4.config

@ -17,7 +17,7 @@ param set MC_ROLLRATE_D 0.001
param set SENS_BOARD_ROT 4 param set SENS_BOARD_ROT 4
sleep 1 sleep 1
mpu9250 start mpu9250 -s start
bmp280 -I start bmp280 -I start
rc_update start rc_update start
sensors start sensors start

2
posix-configs/ocpoc/px4.config

@ -15,7 +15,7 @@ param set MAV_BROADCAST 1
param set MAV_TYPE 2 param set MAV_TYPE 2
param set MAV_SYS_ID 1 param set MAV_SYS_ID 1
mpu9250 -R 10 start mpu9250 -s -R 10 start
hmc5883 -I start hmc5883 -I start
ms5611 -s start ms5611 -s start

2
posix-configs/rpi/px4.config

@ -17,7 +17,7 @@ param set MAV_TYPE 2
dataman start dataman start
mpu9250 -R 8 start mpu9250 -s -R 8 start
lsm9ds1 -s -R 4 start lsm9ds1 -s -R 4 start
lsm9ds1_mag -s -R 4 start lsm9ds1_mag -s -R 4 start
ms5611 -X start ms5611 -X start

2
posix-configs/rpi/px4_fw.config

@ -17,7 +17,7 @@ param set MAV_TYPE 1
dataman start dataman start
mpu9250 -R 8 start mpu9250 -s -R 8 start
lsm9ds1 -s -R 4 start lsm9ds1 -s -R 4 start
lsm9ds1_mag -s -R 4 start lsm9ds1_mag -s -R 4 start
ms5611 -X start ms5611 -X start

2
posix-configs/rpi/px4_test.config

@ -17,7 +17,7 @@ param set MAV_TYPE 2
dataman start dataman start
mpu9250 -R 8 start mpu9250 -s -R 8 start
lsm9ds1 -s -R 4 start lsm9ds1 -s -R 4 start
lsm9ds1_mag -s -R 4 start lsm9ds1_mag -s -R 4 start
ms5611 -X start ms5611 -X start

10
src/drivers/imu/mpu9250/AK8963_I2C.cpp

@ -46,12 +46,12 @@
#ifdef USE_I2C #ifdef USE_I2C
device::Device *AK8963_I2C_interface(int bus); device::Device *AK8963_I2C_interface(int bus, int bus_frequency);
class AK8963_I2C : public device::I2C class AK8963_I2C : public device::I2C
{ {
public: public:
AK8963_I2C(int bus); AK8963_I2C(int bus, int bus_frequency);
~AK8963_I2C() override = default; ~AK8963_I2C() override = default;
int read(unsigned address, void *data, unsigned count) override; int read(unsigned address, void *data, unsigned count) override;
@ -63,12 +63,12 @@ protected:
}; };
device::Device * device::Device *
AK8963_I2C_interface(int bus) AK8963_I2C_interface(int bus, int bus_frequency)
{ {
return new AK8963_I2C(bus); return new AK8963_I2C(bus, bus_frequency);
} }
AK8963_I2C::AK8963_I2C(int bus) : I2C("AK8963_I2C", nullptr, bus, AK8963_I2C_ADDR, 400000) AK8963_I2C::AK8963_I2C(int bus, int bus_frequency) : I2C("AK8963_I2C", nullptr, bus, AK8963_I2C_ADDR, bus_frequency)
{ {
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_MPU9250; _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_MPU9250;
} }

4
src/drivers/imu/mpu9250/MPU9250_mag.h

@ -105,9 +105,7 @@ struct ak8963_regs {
}; };
#pragma pack(pop) #pragma pack(pop)
extern device::Device *AK8963_I2C_interface(int bus); extern device::Device *AK8963_I2C_interface(int bus, int bus_frequency);
typedef device::Device *(*MPU9250_mag_constructor)(int, bool);
/** /**
* Helper class implementing the magnetometer driver node. * Helper class implementing the magnetometer driver node.

22
src/drivers/imu/mpu9250/mpu9250.cpp

@ -70,8 +70,9 @@ const uint16_t MPU9250::_mpu9250_checked_registers[MPU9250_NUM_CHECKED_REGISTERS
MPUREG_INT_PIN_CFG MPUREG_INT_PIN_CFG
}; };
MPU9250::MPU9250(device::Device *interface, device::Device *mag_interface, enum Rotation rotation) : MPU9250::MPU9250(device::Device *interface, device::Device *mag_interface, enum Rotation rotation,
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())), I2CSPIBusOption bus_option, int bus) :
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus),
_interface(interface), _interface(interface),
_px4_accel(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation), _px4_accel(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation),
_px4_gyro(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation), _px4_gyro(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation),
@ -87,9 +88,6 @@ MPU9250::MPU9250(device::Device *interface, device::Device *mag_interface, enum
MPU9250::~MPU9250() MPU9250::~MPU9250()
{ {
// make sure we are truly inactive
stop();
// delete the perf counter // delete the perf counter
perf_free(_sample_perf); perf_free(_sample_perf);
perf_free(_bad_registers); perf_free(_bad_registers);
@ -473,20 +471,11 @@ MPU9250::set_accel_range(unsigned max_g_in)
void void
MPU9250::start() MPU9250::start()
{ {
/* make sure we are stopped first */
stop();
ScheduleOnInterval(_call_interval - MPU9250_TIMER_REDUCTION, 1000); ScheduleOnInterval(_call_interval - MPU9250_TIMER_REDUCTION, 1000);
} }
void void
MPU9250::stop() MPU9250::RunImpl()
{
ScheduleClear();
}
void
MPU9250::Run()
{ {
/* make another measurement */ /* make another measurement */
measure(); measure();
@ -676,8 +665,9 @@ MPU9250::measure()
} }
void void
MPU9250::print_info() MPU9250::print_status()
{ {
I2CSPIDriverBase::print_status();
perf_print_counter(_sample_perf); perf_print_counter(_sample_perf);
perf_print_counter(_bad_registers); perf_print_counter(_bad_registers);
perf_print_counter(_duplicates); perf_print_counter(_duplicates);

31
src/drivers/imu/mpu9250/mpu9250.h

@ -37,13 +37,13 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp> #include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h> #include <lib/ecl/geo/geo.h>
#include <px4_platform_common/getopt.h> #include <px4_platform_common/getopt.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> #include <px4_platform_common/i2c_spi_buses.h>
#include <lib/systemlib/conversions.h> #include <lib/systemlib/conversions.h>
#include <lib/systemlib/px4_macros.h> #include <lib/systemlib/px4_macros.h>
#include "MPU9250_mag.h" #include "MPU9250_mag.h"
#if defined(PX4_I2C_OBDEV_MPU9250) || defined(PX4_I2C_BUS_EXPANSION) #if defined(PX4_I2C_OBDEV_MPU9250)
# define USE_I2C # define USE_I2C
#endif #endif
@ -224,40 +224,42 @@ struct MPUReport {
static constexpr int16_t combine(uint8_t msb, uint8_t lsb) { return (msb << 8u) | lsb; } static constexpr int16_t combine(uint8_t msb, uint8_t lsb) { return (msb << 8u) | lsb; }
/* interface factories */ /* interface factories */
extern device::Device *MPU9250_SPI_interface(int bus, uint32_t cs); extern device::Device *MPU9250_SPI_interface(int bus, uint32_t cs, int bus_frequency, spi_mode_e spi_mode);
extern device::Device *MPU9250_I2C_interface(int bus, uint32_t address); extern device::Device *MPU9250_I2C_interface(int bus, uint32_t address, int bus_frequency);
extern int MPU9250_probe(device::Device *dev);
typedef device::Device *(*MPU9250_constructor)(int, uint32_t);
class MPU9250_mag; class MPU9250_mag;
class MPU9250 : public px4::ScheduledWorkItem class MPU9250 : public I2CSPIDriver<MPU9250>
{ {
public: public:
MPU9250(device::Device *interface, device::Device *mag_interface, enum Rotation rotation); MPU9250(device::Device *interface, device::Device *mag_interface, enum Rotation rotation, I2CSPIBusOption bus_option,
int bus);
virtual ~MPU9250(); virtual ~MPU9250();
virtual int init(); static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance);
static void print_usage();
int init();
uint8_t get_whoami() { return _whoami; } uint8_t get_whoami() { return _whoami; }
/** /**
* Diagnostics - print some basic information about the driver. * Diagnostics - print some basic information about the driver.
*/ */
void print_info(); void print_status() override;
void RunImpl();
protected: protected:
device::Device *_interface; device::Device *_interface;
uint8_t _whoami{0}; /** whoami result */ uint8_t _whoami{0}; /** whoami result */
virtual int probe(); int probe();
friend class MPU9250_mag; friend class MPU9250_mag;
private: private:
void Run() override;
PX4Accelerometer _px4_accel; PX4Accelerometer _px4_accel;
PX4Gyroscope _px4_gyro; PX4Gyroscope _px4_gyro;
@ -300,7 +302,6 @@ private:
bool _got_duplicate{false}; bool _got_duplicate{false};
void start(); void start();
void stop();
int reset(); int reset();
/** /**

10
src/drivers/imu/mpu9250/mpu9250_i2c.cpp

@ -48,7 +48,7 @@ device::Device *MPU9250_I2C_interface(int bus, uint32_t address);
class MPU9250_I2C : public device::I2C class MPU9250_I2C : public device::I2C
{ {
public: public:
MPU9250_I2C(int bus, uint32_t address); MPU9250_I2C(int bus, uint32_t address, int bus_frequency);
~MPU9250_I2C() override = default; ~MPU9250_I2C() override = default;
int read(unsigned address, void *data, unsigned count) override; int read(unsigned address, void *data, unsigned count) override;
@ -62,13 +62,13 @@ private:
}; };
device::Device * device::Device *
MPU9250_I2C_interface(int bus, uint32_t address) MPU9250_I2C_interface(int bus, uint32_t address, int bus_frequency)
{ {
return new MPU9250_I2C(bus, address); return new MPU9250_I2C(bus, address, bus_frequency);
} }
MPU9250_I2C::MPU9250_I2C(int bus, uint32_t address) : MPU9250_I2C::MPU9250_I2C(int bus, uint32_t address, int bus_frequency) :
I2C("MPU9250_I2C", nullptr, bus, address, 400000) I2C("MPU9250_I2C", nullptr, bus, address, bus_frequency)
{ {
set_device_type(DRV_IMU_DEVTYPE_MPU9250); set_device_type(DRV_IMU_DEVTYPE_MPU9250);
} }

244
src/drivers/imu/mpu9250/mpu9250_main.cpp

@ -31,234 +31,106 @@
* *
****************************************************************************/ ****************************************************************************/
#include <px4_platform_common/px4_config.h> #include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/getopt.h> #include <px4_platform_common/module.h>
#include "mpu9250.h" #include "mpu9250.h"
enum class MPU9250_BUS { void
ALL = 0, MPU9250::print_usage()
I2C_INTERNAL,
I2C_EXTERNAL,
SPI_INTERNAL,
SPI_INTERNAL2,
SPI_EXTERNAL
};
namespace mpu9250
{ {
PRINT_MODULE_USAGE_NAME("mpu9250", "driver");
// list of supported bus configurations PRINT_MODULE_USAGE_SUBCATEGORY("imu");
struct mpu9250_bus_option { PRINT_MODULE_USAGE_COMMAND("start");
MPU9250_BUS busid; PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true);
MPU9250_constructor interface_constructor; PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
bool magpassthrough; PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
uint8_t busnum;
uint32_t address;
MPU9250 *dev;
} bus_options[] = {
#if defined(USE_I2C)
# if defined(PX4_I2C_BUS_ONBOARD) && defined(PX4_I2C_OBDEV_MPU9250)
{ MPU9250_BUS::I2C_INTERNAL, &MPU9250_I2C_interface, false, PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_MPU9250, nullptr },
# endif
# if defined(PX4_I2C_BUS_EXPANSION) && defined(PX4_I2C_OBDEV_MPU9250)
{ MPU9250_BUS::I2C_EXTERNAL, &MPU9250_I2C_interface, false, PX4_I2C_BUS_EXPANSION, PX4_I2C_OBDEV_MPU9250, nullptr },
# endif
# if defined(PX4_I2C_BUS_EXPANSION1) && defined(PX4_I2C_OBDEV_MPU9250)
{ MPU9250_BUS::I2C_EXTERNAL, &MPU9250_I2C_interface, false, PX4_I2C_BUS_EXPANSION1, PX4_I2C_OBDEV_MPU9250, nullptr },
# endif
# if defined(PX4_I2C_BUS_EXPANSION2) && defined(PX4_I2C_OBDEV_MPU9250)
{ MPU9250_BUS::I2C_EXTERNAL, &MPU9250_I2C_interface, false, PX4_I2C_BUS_EXPANSION2, PX4_I2C_OBDEV_MPU9250, nullptr },
# endif
#endif
#if defined(PX4_SPI_BUS_SENSORS) && defined(PX4_SPIDEV_MPU)
{ MPU9250_BUS::SPI_INTERNAL, &MPU9250_SPI_interface, true, PX4_SPI_BUS_SENSORS, PX4_SPIDEV_MPU, nullptr },
#endif
#if defined(PX4_SPI_BUS_SENSORS) && defined(PX4_SPIDEV_MPU2)
{ MPU9250_BUS::SPI_INTERNAL2, &MPU9250_SPI_interface, true, PX4_SPI_BUS_SENSORS, PX4_SPIDEV_MPU2, nullptr },
#endif
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_MPU)
{ MPU9250_BUS::SPI_EXTERNAL, &MPU9250_SPI_interface, true, PX4_SPI_BUS_EXT, PX4_SPIDEV_EXT_MPU, nullptr },
#endif
};
// find a bus structure for a busid
static mpu9250_bus_option *find_bus(MPU9250_BUS busid)
{
for (mpu9250_bus_option &bus_option : bus_options) {
if ((busid == MPU9250_BUS::ALL ||
busid == bus_option.busid) && bus_option.dev != nullptr) {
return &bus_option;
}
}
return nullptr;
} }
static bool start_bus(mpu9250_bus_option &bus, enum Rotation rotation) I2CSPIDriverBase *MPU9250::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance)
{ {
device::Device *interface = bus.interface_constructor(bus.busnum, bus.address); device::Device *interface = nullptr;
if ((interface == nullptr) || (interface->init() != PX4_OK)) {
PX4_WARN("no device on bus %u", (unsigned)bus.busid);
delete interface;
return false;
}
device::Device *mag_interface = nullptr; device::Device *mag_interface = nullptr;
if (iterator.busType() == BOARD_I2C_BUS) {
#ifdef USE_I2C #ifdef USE_I2C
interface = MPU9250_I2C_interface(iterator.bus(), PX4_I2C_OBDEV_MPU9250, cli.bus_frequency);
// For i2c interfaces, connect to the magnetomer directly // For i2c interfaces, connect to the magnetomer directly
if ((bus.busid == MPU9250_BUS::I2C_INTERNAL) || (bus.busid == MPU9250_BUS::I2C_EXTERNAL)) { mag_interface = AK8963_I2C_interface(iterator.bus(), cli.bus_frequency);
mag_interface = AK8963_I2C_interface(bus.busnum);
}
#endif // USE_I2C #endif // USE_I2C
MPU9250 *dev = new MPU9250(interface, mag_interface, rotation); } else if (iterator.busType() == BOARD_SPI_BUS) {
interface = MPU9250_SPI_interface(iterator.bus(), iterator.devid(), cli.bus_frequency, cli.spi_mode);
}
if (dev == nullptr) { if (interface == nullptr) {
PX4_ERR("alloc failed"); PX4_ERR("alloc failed");
delete mag_interface; delete mag_interface;
return false; return nullptr;
} }
if (dev->init() != PX4_OK) { if (interface->init() != OK) {
PX4_ERR("driver start failed"); delete interface;
delete dev;
delete mag_interface; delete mag_interface;
return false; PX4_DEBUG("no device on bus %i (devid 0x%x)", iterator.bus(), iterator.devid());
return nullptr;
} }
bus.dev = dev; MPU9250 *dev = new MPU9250(interface, mag_interface, cli.rotation, iterator.configuredBusOption(), iterator.bus());
return true;
}
static int start(MPU9250_BUS busid, enum Rotation rotation)
{
for (mpu9250_bus_option &bus_option : bus_options) {
if (bus_option.dev != nullptr) {
// this device is already started
PX4_WARN("already started");
continue;
}
if (busid != MPU9250_BUS::ALL && bus_option.busid != busid) {
// not the one that is asked for
continue;
}
if (start_bus(bus_option, rotation)) {
return 0;
}
}
return -1;
}
static int stop(MPU9250_BUS busid)
{
mpu9250_bus_option *bus = find_bus(busid);
if (bus != nullptr && bus->dev != nullptr) { if (dev == nullptr) {
delete bus->dev; delete interface;
bus->dev = nullptr; delete mag_interface;
return nullptr;
} else {
PX4_WARN("driver not running");
return -1;
} }
return 0; if (OK != dev->init()) {
} delete dev;
return nullptr;
static int status(MPU9250_BUS busid)
{
mpu9250_bus_option *bus = find_bus(busid);
if (bus != nullptr && bus->dev != nullptr) {
bus->dev->print_info();
return 0;
} }
PX4_WARN("driver not running"); return dev;
return -1;
}
static int usage()
{
PX4_INFO("missing command: try 'start', 'stop', 'status'");
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");
return 0;
} }
} // namespace extern "C" int
mpu9250_main(int argc, char *argv[])
extern "C" int mpu9250_main(int argc, char *argv[])
{ {
int myoptind = 1;
int ch; int ch;
const char *myoptarg = nullptr; using ThisDriver = MPU9250;
BusCLIArguments cli{true, true};
MPU9250_BUS busid = MPU9250_BUS::ALL; cli.default_spi_frequency = 1000 * 1000; // low speed bus frequency
enum Rotation rotation = ROTATION_NONE; cli.default_i2c_frequency = 400000;
while ((ch = px4_getopt(argc, argv, "XISstR:", &myoptind, &myoptarg)) != EOF) { while ((ch = cli.getopt(argc, argv, "R:")) != EOF) {
switch (ch) { switch (ch) {
case 'X':
busid = MPU9250_BUS::I2C_EXTERNAL;
break;
case 'I':
busid = MPU9250_BUS::I2C_INTERNAL;
break;
case 'S':
busid = MPU9250_BUS::SPI_EXTERNAL;
break;
case 's':
busid = MPU9250_BUS::SPI_INTERNAL;
break;
case 't':
busid = MPU9250_BUS::SPI_INTERNAL2;
break;
case 'R': case 'R':
rotation = (enum Rotation)atoi(myoptarg); cli.rotation = (enum Rotation)atoi(cli.optarg());
break; break;
default:
return mpu9250::usage();
} }
} }
if (myoptind >= argc) { const char *verb = cli.optarg();
return mpu9250::usage();
if (!verb) {
ThisDriver::print_usage();
return -1;
} }
const char *verb = argv[myoptind]; BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_MPU9250);
if (!strcmp(verb, "start")) { if (!strcmp(verb, "start")) {
return mpu9250::start(busid, rotation); return ThisDriver::module_start(cli, iterator);
}
} else if (!strcmp(verb, "stop")) { if (!strcmp(verb, "stop")) {
return mpu9250::stop(busid); return ThisDriver::module_stop(iterator);
}
} else if (!strcmp(verb, "status")) { if (!strcmp(verb, "status")) {
return mpu9250::status(busid); return ThisDriver::module_status(iterator);
} }
return mpu9250::usage(); ThisDriver::print_usage();
return -1;
} }

12
src/drivers/imu/mpu9250/mpu9250_spi.cpp

@ -59,12 +59,12 @@
#define MPU9250_LOW_SPI_BUS_SPEED 1000*1000 #define MPU9250_LOW_SPI_BUS_SPEED 1000*1000
#define MPU9250_HIGH_SPI_BUS_SPEED 20*1000*1000 #define MPU9250_HIGH_SPI_BUS_SPEED 20*1000*1000
device::Device *MPU9250_SPI_interface(int bus, uint32_t cs); device::Device *MPU9250_SPI_interface(int bus, uint32_t cs, int bus_frequency, spi_mode_e spi_mode);
class MPU9250_SPI : public device::SPI class MPU9250_SPI : public device::SPI
{ {
public: public:
MPU9250_SPI(int bus, uint32_t device); MPU9250_SPI(int bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode);
~MPU9250_SPI() override = default; ~MPU9250_SPI() override = default;
int read(unsigned address, void *data, unsigned count) override; int read(unsigned address, void *data, unsigned count) override;
@ -80,13 +80,13 @@ private:
}; };
device::Device * device::Device *
MPU9250_SPI_interface(int bus, uint32_t cs) MPU9250_SPI_interface(int bus, uint32_t cs, int bus_frequency, spi_mode_e spi_mode)
{ {
return new MPU9250_SPI(bus, cs); return new MPU9250_SPI(bus, cs, bus_frequency, spi_mode);
} }
MPU9250_SPI::MPU9250_SPI(int bus, uint32_t device) : MPU9250_SPI::MPU9250_SPI(int bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("MPU9250", nullptr, bus, device, SPIDEV_MODE3, MPU9250_LOW_SPI_BUS_SPEED) SPI("MPU9250", nullptr, bus, device, spi_mode, bus_frequency)
{ {
set_device_type(DRV_IMU_DEVTYPE_MPU9250); set_device_type(DRV_IMU_DEVTYPE_MPU9250);
} }

Loading…
Cancel
Save