Added build specific sensor initialization.

This commit is contained in:
jwilson 2016-02-17 21:02:13 -08:00 committed by Julian Oes
parent 75fad09263
commit ebfcf32323
4 changed files with 163 additions and 26 deletions

View File

@ -30,6 +30,15 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
set(SENSORS_SRCS sensors.cpp)
if (${OS} STREQUAL "qurt")
list(APPEND SENSORS_SRCS
sensors_init_qurt.cpp)
elseif(${OS} STREQUAL "nuttx")
list(APPEND SENSORS_SRCS
sensors_init_nuttx.cpp)
endif()
px4_add_module(
MODULE modules__sensors
MAIN sensors
@ -39,7 +48,7 @@ px4_add_module(
-Wno-type-limits
-O3
SRCS
sensors.cpp
${SENSORS_SRCS}
DEPENDS
platforms__common
)

View File

@ -105,6 +105,9 @@
using namespace DriverFramework;
/* Platform specific sensor initialization function. */
extern int sensors_init(void);
/**
* Analog layout:
* FMU:
@ -2098,33 +2101,39 @@ Sensors::task_main()
/* start individual sensors */
int ret = 0;
do { /* create a scope to handle exit with break */
#ifndef __PX4_QURT
// TODO: needs fixes for QURT.
ret = accel_init();
if (ret) { break; }
// TODO-JYW: TESTING-TESTING:
ret = sensors_init();
ret = gyro_init();
if (ret) { break; }
ret = mag_init();
if (ret) { break; }
ret = baro_init();
if (ret) { break; }
ret = adc_init();
if (ret) { break; }
#endif
break;
} while (0);
///*
// * QURT devices do not yet use DriverFramework based drivers, which is required for
// * the following initialization sequence to work correctly.
// */
//#ifndef __PX4_QURT
// do { /* create a scope to handle exit with break */
// ret = accel_init();
//
// if (ret) { break; }
//
// ret = gyro_init();
//
// if (ret) { break; }
//
// ret = mag_init();
//
// if (ret) { break; }
//
// ret = baro_init();
//
// if (ret) { break; }
//
// ret = adc_init();
//
// if (ret) { break; }
//
// break;
// } while (0);
//#endif
if (ret) {
warnx("sensor initialization failed");

View File

@ -0,0 +1,71 @@
/****************************************************************************
*
* Copyright (c) 2015 James Wilson. 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.
*
****************************************************************************/
/**
* @file sensors_init_nuttx.cpp
*
* Sensor initialization code, used only in Nuttx platform builds.
*
* @author James Wilson <jywilson99@hotmail.com>
*/
int
sensors_init(void)
{
int ret;
ret = accel_init();
if (ret) { return ret; }
ret = gyro_init();
if (ret) { return ret; }
ret = mag_init();
if (ret) { return ret; }
ret = baro_init();
if (ret) { return ret; }
ret = adc_init();
if (ret) { return ret; }
return 0;
}

View File

@ -0,0 +1,48 @@
/****************************************************************************
*
* Copyright (c) 2015 James Wilson. 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.
*
****************************************************************************/
/**
* @file sensors_init_qurt.cpp
*
* Sensor initialization code, used only in QuRT platform builds.
*
* @author James Wilson <jywilson99@hotmail.com>
*/
int
sensors_init(void)
{
// Sensor initialization is performed automatically when the QuRT sensor drivers
// are loaded.
return 0;
}