Skip to content

Commit

Permalink
Merge pull request #2 from PX4/integration3_mpu
Browse files Browse the repository at this point in the history
Integration3 MPU bringup
  • Loading branch information
mcharleb committed Feb 9, 2016
2 parents 4e128fc + 405decd commit e1c96c4
Show file tree
Hide file tree
Showing 10 changed files with 303 additions and 53 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -346,6 +346,7 @@ endforeach()
add_subdirectory(src/firmware/${OS})

add_subdirectory(src/lib/DriverFramework/framework/src)
add_subdirectory(src/lib/DriverFramework/drivers/)
#add_dependencies(df_driver_framework nuttx_export_${CONFIG}.stamp)
if (NOT "${OS}" STREQUAL "nuttx")
endif()
Expand Down
1 change: 1 addition & 0 deletions cmake/common/px4_base.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -630,6 +630,7 @@ function(px4_add_common_flags)
${CMAKE_BINARY_DIR}/src/modules
${CMAKE_SOURCE_DIR}/mavlink/include/mavlink
${CMAKE_SOURCE_DIR}/src/lib/DriverFramework/framework/include
${CMAKE_SOURCE_DIR}/src/lib/DriverFramework/drivers/imu
)

list(APPEND added_include_dirs
Expand Down
1 change: 1 addition & 0 deletions cmake/configs/posix_eagle_default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ set(config_module_list
systemcmds/param
systemcmds/mixer
systemcmds/ver
systemcmds/topic_listener

modules/mavlink

Expand Down
1 change: 1 addition & 0 deletions cmake/configs/posix_sitl_default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ set(config_module_list
platforms/posix/drivers/gyrosim
platforms/posix/drivers/rgbledsim
platforms/posix/drivers/ledsim
platforms/posix/drivers/df_imu
systemcmds/param
systemcmds/mixer
systemcmds/ver
Expand Down
1 change: 1 addition & 0 deletions cmake/configs/qurt_eagle_default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ set(config_module_list
# $(EAGLE_DRIVERS_SRC)/uart_esc
# $(EAGLE_DRIVERS_SRC)/rc_receiver
# $(EAGLE_DRIVERS_SRC)/csr_gps
platforms/posix/drivers/df_imu

#
# System commands
Expand Down
5 changes: 0 additions & 5 deletions posix-configs/eagle/flight/mainapp-flight.config
Original file line number Diff line number Diff line change
@@ -1,7 +1,2 @@
uorb start
muorb start
mavlink start -u 14556
sleep 1
mavlink stream -u 14556 -s HIGHRES_IMU -r 50
mavlink stream -u 14556 -s ATTITUDE -r 50
mavlink boot_complete
50 changes: 3 additions & 47 deletions posix-configs/eagle/flight/px4-flight.config
Original file line number Diff line number Diff line change
@@ -1,57 +1,13 @@
uorb start
param set CAL_GYRO0_ID 2293760
param set CAL_ACC0_ID 1310720
param set CAL_ACC1_ID 1376256
param set CAL_MAG0_ID 196608
sleep 1
df_imu start
sensors start
commander start
param set RC_RECEIVER_TYPE 1
rc_receiver start -D /dev/tty-1
attitude_estimator_q start
position_estimator_inav start
mc_pos_control start
mc_att_control start
sleep 1
param set RC_MAP_THROTTLE 1
param set RC_MAP_ROLL 2
param set RC_MAP_PITCH 3
param set RC_MAP_YAW 4
param set RC_MAP_MODE_SW 5
param set RC_MAP_POSCTL_SW 6
param set RC1_MAX 1900
param set RC1_MIN 1099
param set RC1_TRIM 1099
param set RC1_REV 1
param set RC2_MAX 1900
param set RC2_MIN 1099
param set RC2_TRIM 1500
param set RC2_REV -1
param set RC3_MAX 1900
param set RC3_MIN 1099
param set RC3_TRIM 1500
param set RC3_REV 1
param set RC4_MAX 1900
param set RC4_MIN 1099
param set RC4_TRIM 1500
param set RC4_REV -1
param set RC5_MAX 1900
param set RC5_MIN 1099
param set RC5_TRIM 1500
param set RC5_REV 1
param set RC6_MAX 1900
param set RC6_MIN 1099
param set RC6_TRIM 1099
param set RC6_REV 1
sensors start
param set ATT_W_MAG 0.00
param set PE_MAG_NOISE 1.0f
param set MPU_GYRO_LPF_ENUM 4
param set MPU_ACC_LPF_ENUM 4
param set MPU_SAMPLE_RATE_ENUM 2
sleep 1
mpu9x50 start -D /dev/spi-1
uart_esc start -D /dev/tty-2
csr_gps start -D /dev/tty-3
pressure start -D /dev/i2c-2
list_devices
list_files
list_tasks
Expand Down
2 changes: 1 addition & 1 deletion src/lib/DriverFramework
Submodule DriverFramework updated 55 files
+3 −0 CMakeLists.txt
+8 −6 Makefile
+47 −17 drivers/i2c/I2CDevObj.cpp
+36 −3 drivers/imu/ImuSensor.hpp
+260 −27 drivers/imu/mpu9250/MPU9250.cpp
+7 −3 drivers/imu/mpu9250/MPU9250.hpp
+1 −1 drivers/imu/test/main.cpp
+31 −37 drivers/imu/test/test.cpp
+11 −7 drivers/pressure/PressureSensor.hpp
+90 −39 drivers/pressure/bmp280/BMP280.cpp
+1 −0 drivers/pressure/bmp280/BMP280.hpp
+7 −17 drivers/pressure/test/test.cpp
+205 −94 drivers/spi/SPIDevObj.cpp
+1 −1 dspal
+52 −0 framework/include/DFDiag.hpp
+5 −5 framework/include/DFList.hpp
+16 −16 framework/include/DFLog.hpp
+94 −0 framework/include/DFTest.hpp
+6 −6 framework/include/DevIOCTL.h
+1 −2 framework/include/DevMgr.hpp
+10 −8 framework/include/DevObj.hpp
+1 −4 framework/include/DriverFramework.hpp
+10 −7 framework/include/I2CDevObj.hpp
+6 −6 framework/include/OSConfig.h
+22 −6 framework/include/SPIDevObj.hpp
+1 −1 framework/include/SyncObj.hpp
+0 −3 framework/include/WorkMgr.hpp
+1 −0 framework/src/CMakeLists.txt
+88 −0 framework/src/DFDiag.cpp
+5 −4 framework/src/DFList.cpp
+4 −26 framework/src/DevMgr.cpp
+21 −8 framework/src/DevObj.cpp
+13 −10 framework/src/DriverFramework.cpp
+20 −12 framework/src/SyncObj.cpp
+42 −0 framework/test/CMakeLists.txt
+59 −0 framework/test/DFFrameworkTest.cpp
+50 −0 framework/test/DFFrameworkTest.hpp
+91 −43 framework/test/DFListTest.cpp
+71 −0 framework/test/DFListTest.hpp
+159 −0 framework/test/DevMgrTest.cpp
+58 −0 framework/test/DevMgrTest.hpp
+66 −0 framework/test/SyncObjTest.cpp
+53 −0 framework/test/SyncObjTest.hpp
+68 −0 framework/test/TimeTest.cpp
+54 −0 framework/test/TimeTest.hpp
+0 −0 framework/test/testdriver.hpp
+0 −152 os/qurt/include/dev_fs_lib_i2c.h
+0 −160 os/qurt/include/dev_fs_lib_spi.h
+6 −0 os/qurt/src/qurt_stubs.cpp
+2 −1 test/CMakeLists.txt
+146 −0 test/driver.cpp
+2 −2 test/main.cpp
+0 −1 test/qurt/CMakeLists.txt
+2 −2 test/qurt/df_testapp_dsp.cpp
+4 −150 test/test.cpp
42 changes: 42 additions & 0 deletions src/platforms/posix/drivers/df_imu/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
############################################################################
#
# Copyright (c) 2016 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 platforms__posix__drivers__df_imu
MAIN df_imu
SRCS
df_imu.cpp
DEPENDS
platforms__common
df_driver_framework
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
Loading

0 comments on commit e1c96c4

Please sign in to comment.