Browse Source

MindPX: Remove MPU6500 driver, use MPU9K driver instead

sbg
Henry Zhang 8 years ago committed by Lorenz Meier
parent
commit
92fc82da33
  1. 6
      ROMFS/px4fmu_common/init.d/rc.sensors
  2. 13
      ROMFS/px4fmu_test/init.d/rc.sensors
  3. 5
      cmake/configs/nuttx_mindpx-v2_default.cmake
  4. 43
      src/drivers/mpu6500/CMakeLists.txt
  5. 2368
      src/drivers/mpu6500/mpu6500.cpp
  6. 2
      src/drivers/mpu9250/mpu9250_spi.cpp

6
ROMFS/px4fmu_common/init.d/rc.sensors

@ -225,7 +225,7 @@ then @@ -225,7 +225,7 @@ then
if bmi055 -A start
then
fi
# Internal SPI bus BMI055_GYR
if bmi055 -G start
then
@ -235,7 +235,7 @@ then @@ -235,7 +235,7 @@ then
if bmm150 -R 2 start
then
fi
# expansion i2c used for BMP280
if bmp280 -I start
then
@ -287,7 +287,7 @@ then @@ -287,7 +287,7 @@ then
then
fi
if mpu6500 -R 8 start
if mpu9250 -s -R 8 start
then
fi

13
ROMFS/px4fmu_test/init.d/rc.sensors

@ -156,24 +156,25 @@ fi @@ -156,24 +156,25 @@ fi
if ver hwcmp MINDPX_V2
then
if mpu6500 start
# External I2C bus
if hmc5883 -C -T -X start
then
fi
if lsm303d start
# Internal I2C bus
if hmc5883 -C -T -I -R 12 start
then
fi
if l3gd20 start
if mpu9250 -s -R 8 start
then
fi
# External I2C bus
if hmc5883 -C -T -X start
if lsm303d -R 10 start
then
fi
if lis3mdl -R 2 start
if l3gd20 -R 14 start
then
fi
fi

5
cmake/configs/nuttx_mindpx-v2_default.cmake

@ -19,10 +19,7 @@ set(config_module_list @@ -19,10 +19,7 @@ set(config_module_list
drivers/boards/mindpx-v2
drivers/rgbled
#drivers/rgbled_pwm
#drivers/mpu6000
#drivers/mpu6050
drivers/mpu6500
#drivers/mpu9250
drivers/mpu9250
drivers/lsm303d
drivers/l3gd20
drivers/hmc5883

43
src/drivers/mpu6500/CMakeLists.txt

@ -1,43 +0,0 @@ @@ -1,43 +0,0 @@
############################################################################
#
# Copyright (c) 2015 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.
#
############################################################################
px4_add_module(
MODULE drivers__mpu6500
MAIN mpu6500
STACK_MAIN 1200
COMPILE_FLAGS
SRCS
mpu6500.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

2368
src/drivers/mpu6500/mpu6500.cpp

File diff suppressed because it is too large Load Diff

2
src/drivers/mpu9250/mpu9250_spi.cpp

@ -113,7 +113,7 @@ MPU9250_SPI_interface(int bus, bool external_bus) @@ -113,7 +113,7 @@ MPU9250_SPI_interface(int bus, bool external_bus)
device::Device *interface = nullptr;
if (external_bus) {
#ifdef PX4_SPI_BUS_EXT
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_MPU)
cs = (spi_dev_e) PX4_SPIDEV_EXT_MPU;
#else
errx(0, "External SPI not available");

Loading…
Cancel
Save