mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Saving files before refreshing line endings
This commit is contained in:
parent
876cf6bdd7
commit
4237370b60
3 changed files with 724 additions and 724 deletions
|
@ -1,213 +1,213 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs
|
* Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs
|
||||||
*
|
*
|
||||||
* All rights reserved.
|
* All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without modification,
|
* Redistribution and use in source and binary forms, with or without modification,
|
||||||
* are permitted provided that the following conditions are met:
|
* are permitted provided that the following conditions are met:
|
||||||
*
|
*
|
||||||
* Redistributions of source code must retain the above copyright notice, this list
|
* Redistributions of source code must retain the above copyright notice, this list
|
||||||
* of conditions and the following disclaimer.
|
* of conditions and the following disclaimer.
|
||||||
*
|
*
|
||||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||||
* list of conditions and the following disclaimer in the documentation and/or other
|
* list of conditions and the following disclaimer in the documentation and/or other
|
||||||
* materials provided with the distribution.
|
* materials provided with the distribution.
|
||||||
*
|
*
|
||||||
* Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its
|
* Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its
|
||||||
* contributors may be used to endorse or promote products derived from this software
|
* contributors may be used to endorse or promote products derived from this software
|
||||||
* without specific prior written permission.
|
* without specific prior written permission.
|
||||||
*
|
*
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
* 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
|
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||||
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
|
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
|
||||||
* IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
|
* IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
|
||||||
* INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
* INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
|
* 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,
|
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||||
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
* 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
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
|
||||||
* OF SUCH DAMAGE.
|
* OF SUCH DAMAGE.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdarg.h>
|
#include <stdarg.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "build_config.h"
|
#include "build_config.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
#include "build_config.h"
|
#include "build_config.h"
|
||||||
#include "printf.h"
|
#include "printf.h"
|
||||||
|
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
#include "typeconversion.h"
|
#include "typeconversion.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static serialPort_t *printfSerialPort;
|
static serialPort_t *printfSerialPort;
|
||||||
|
|
||||||
#ifdef REQUIRE_CC_ARM_PRINTF_SUPPORT
|
#ifdef REQUIRE_CC_ARM_PRINTF_SUPPORT
|
||||||
|
|
||||||
typedef void (*putcf) (void *, char);
|
typedef void (*putcf) (void *, char);
|
||||||
static putcf stdout_putf;
|
static putcf stdout_putf;
|
||||||
static void *stdout_putp;
|
static void *stdout_putp;
|
||||||
|
|
||||||
static void putchw(void *putp, putcf putf, int n, char z, char *bf)
|
static void putchw(void *putp, putcf putf, int n, char z, char *bf)
|
||||||
{
|
{
|
||||||
char fc = z ? '0' : ' ';
|
char fc = z ? '0' : ' ';
|
||||||
char ch;
|
char ch;
|
||||||
char *p = bf;
|
char *p = bf;
|
||||||
while (*p++ && n > 0)
|
while (*p++ && n > 0)
|
||||||
n--;
|
n--;
|
||||||
while (n-- > 0)
|
while (n-- > 0)
|
||||||
putf(putp, fc);
|
putf(putp, fc);
|
||||||
while ((ch = *bf++))
|
while ((ch = *bf++))
|
||||||
putf(putp, ch);
|
putf(putp, ch);
|
||||||
}
|
}
|
||||||
|
|
||||||
void tfp_format(void *putp, putcf putf, char *fmt, va_list va)
|
void tfp_format(void *putp, putcf putf, char *fmt, va_list va)
|
||||||
{
|
{
|
||||||
char bf[12];
|
char bf[12];
|
||||||
|
|
||||||
char ch;
|
char ch;
|
||||||
|
|
||||||
while ((ch = *(fmt++))) {
|
while ((ch = *(fmt++))) {
|
||||||
if (ch != '%')
|
if (ch != '%')
|
||||||
putf(putp, ch);
|
putf(putp, ch);
|
||||||
else {
|
else {
|
||||||
char lz = 0;
|
char lz = 0;
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
char lng = 0;
|
char lng = 0;
|
||||||
#endif
|
#endif
|
||||||
int w = 0;
|
int w = 0;
|
||||||
ch = *(fmt++);
|
ch = *(fmt++);
|
||||||
if (ch == '0') {
|
if (ch == '0') {
|
||||||
ch = *(fmt++);
|
ch = *(fmt++);
|
||||||
lz = 1;
|
lz = 1;
|
||||||
}
|
}
|
||||||
if (ch >= '0' && ch <= '9') {
|
if (ch >= '0' && ch <= '9') {
|
||||||
ch = a2i(ch, &fmt, 10, &w);
|
ch = a2i(ch, &fmt, 10, &w);
|
||||||
}
|
}
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (ch == 'l') {
|
if (ch == 'l') {
|
||||||
ch = *(fmt++);
|
ch = *(fmt++);
|
||||||
lng = 1;
|
lng = 1;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
switch (ch) {
|
switch (ch) {
|
||||||
case 0:
|
case 0:
|
||||||
goto abort;
|
goto abort;
|
||||||
case 'u':{
|
case 'u':{
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (lng)
|
if (lng)
|
||||||
uli2a(va_arg(va, unsigned long int), 10, 0, bf);
|
uli2a(va_arg(va, unsigned long int), 10, 0, bf);
|
||||||
else
|
else
|
||||||
#endif
|
#endif
|
||||||
ui2a(va_arg(va, unsigned int), 10, 0, bf);
|
ui2a(va_arg(va, unsigned int), 10, 0, bf);
|
||||||
putchw(putp, putf, w, lz, bf);
|
putchw(putp, putf, w, lz, bf);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case 'd':{
|
case 'd':{
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (lng)
|
if (lng)
|
||||||
li2a(va_arg(va, unsigned long int), bf);
|
li2a(va_arg(va, unsigned long int), bf);
|
||||||
else
|
else
|
||||||
#endif
|
#endif
|
||||||
i2a(va_arg(va, int), bf);
|
i2a(va_arg(va, int), bf);
|
||||||
putchw(putp, putf, w, lz, bf);
|
putchw(putp, putf, w, lz, bf);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case 'x':
|
case 'x':
|
||||||
case 'X':
|
case 'X':
|
||||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||||
if (lng)
|
if (lng)
|
||||||
uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf);
|
uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf);
|
||||||
else
|
else
|
||||||
#endif
|
#endif
|
||||||
ui2a(va_arg(va, unsigned int), 16, (ch == 'X'), bf);
|
ui2a(va_arg(va, unsigned int), 16, (ch == 'X'), bf);
|
||||||
putchw(putp, putf, w, lz, bf);
|
putchw(putp, putf, w, lz, bf);
|
||||||
break;
|
break;
|
||||||
case 'c':
|
case 'c':
|
||||||
putf(putp, (char) (va_arg(va, int)));
|
putf(putp, (char) (va_arg(va, int)));
|
||||||
break;
|
break;
|
||||||
case 's':
|
case 's':
|
||||||
putchw(putp, putf, w, 0, va_arg(va, char *));
|
putchw(putp, putf, w, 0, va_arg(va, char *));
|
||||||
break;
|
break;
|
||||||
case '%':
|
case '%':
|
||||||
putf(putp, ch);
|
putf(putp, ch);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
abort:;
|
abort:;
|
||||||
}
|
}
|
||||||
|
|
||||||
void init_printf(void *putp, void (*putf) (void *, char))
|
void init_printf(void *putp, void (*putf) (void *, char))
|
||||||
{
|
{
|
||||||
stdout_putf = putf;
|
stdout_putf = putf;
|
||||||
stdout_putp = putp;
|
stdout_putp = putp;
|
||||||
}
|
}
|
||||||
|
|
||||||
void tfp_printf(char *fmt, ...)
|
void tfp_printf(char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list va;
|
va_list va;
|
||||||
va_start(va, fmt);
|
va_start(va, fmt);
|
||||||
tfp_format(stdout_putp, stdout_putf, fmt, va);
|
tfp_format(stdout_putp, stdout_putf, fmt, va);
|
||||||
va_end(va);
|
va_end(va);
|
||||||
while (!isSerialTransmitBufferEmpty(printfSerialPort));
|
while (!isSerialTransmitBufferEmpty(printfSerialPort));
|
||||||
}
|
}
|
||||||
|
|
||||||
static void putcp(void *p, char c)
|
static void putcp(void *p, char c)
|
||||||
{
|
{
|
||||||
*(*((char **) p))++ = c;
|
*(*((char **) p))++ = c;
|
||||||
}
|
}
|
||||||
|
|
||||||
void tfp_sprintf(char *s, char *fmt, ...)
|
void tfp_sprintf(char *s, char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list va;
|
va_list va;
|
||||||
|
|
||||||
va_start(va, fmt);
|
va_start(va, fmt);
|
||||||
tfp_format(&s, putcp, fmt, va);
|
tfp_format(&s, putcp, fmt, va);
|
||||||
putcp(&s, 0);
|
putcp(&s, 0);
|
||||||
va_end(va);
|
va_end(va);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
static void _putc(void *p, char c)
|
static void _putc(void *p, char c)
|
||||||
{
|
{
|
||||||
UNUSED(p);
|
UNUSED(p);
|
||||||
serialWrite(printfSerialPort, c);
|
serialWrite(printfSerialPort, c);
|
||||||
}
|
}
|
||||||
|
|
||||||
void initPrintfSupport(void)
|
void initPrintfSupport(void)
|
||||||
{
|
{
|
||||||
init_printf(NULL, _putc);
|
init_printf(NULL, _putc);
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
// keil/armcc version
|
// keil/armcc version
|
||||||
int fputc(int c, FILE *f)
|
int fputc(int c, FILE *f)
|
||||||
{
|
{
|
||||||
// let DMA catch up a bit when using set or dump, we're too fast.
|
// let DMA catch up a bit when using set or dump, we're too fast.
|
||||||
while (!isSerialTransmitBufferEmpty(serialPorts.mainport));
|
while (!isSerialTransmitBufferEmpty(serialPorts.mainport));
|
||||||
serialWrite(printfSerialPort, c);
|
serialWrite(printfSerialPort, c);
|
||||||
return c;
|
return c;
|
||||||
}
|
}
|
||||||
|
|
||||||
void initPrintfSupport(serialPort_t *serialPort)
|
void initPrintfSupport(serialPort_t *serialPort)
|
||||||
{
|
{
|
||||||
// Nothing to do
|
// Nothing to do
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void setPrintfSerialPort(serialPort_t *serialPort)
|
void setPrintfSerialPort(serialPort_t *serialPort)
|
||||||
{
|
{
|
||||||
printfSerialPort = serialPort;
|
printfSerialPort = serialPort;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,439 +1,439 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "build_config.h"
|
#include "build_config.h"
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
|
|
||||||
#include "drivers/accgyro_adxl345.h"
|
#include "drivers/accgyro_adxl345.h"
|
||||||
#include "drivers/accgyro_bma280.h"
|
#include "drivers/accgyro_bma280.h"
|
||||||
#include "drivers/accgyro_l3g4200d.h"
|
#include "drivers/accgyro_l3g4200d.h"
|
||||||
#include "drivers/accgyro_mma845x.h"
|
#include "drivers/accgyro_mma845x.h"
|
||||||
#include "drivers/accgyro_mpu3050.h"
|
#include "drivers/accgyro_mpu3050.h"
|
||||||
#include "drivers/accgyro_mpu6050.h"
|
#include "drivers/accgyro_mpu6050.h"
|
||||||
#ifdef STM32F3DISCOVERY
|
#ifdef STM32F3DISCOVERY
|
||||||
#include "drivers/accgyro_l3gd20.h"
|
#include "drivers/accgyro_l3gd20.h"
|
||||||
#include "drivers/accgyro_lsm303dlhc.h"
|
#include "drivers/accgyro_lsm303dlhc.h"
|
||||||
#endif
|
#endif
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
#include "drivers/accgyro_spi_mpu6000.h"
|
#include "drivers/accgyro_spi_mpu6000.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "drivers/barometer.h"
|
#include "drivers/barometer.h"
|
||||||
#include "drivers/barometer_bmp085.h"
|
#include "drivers/barometer_bmp085.h"
|
||||||
#include "drivers/barometer_ms5611.h"
|
#include "drivers/barometer_ms5611.h"
|
||||||
#include "drivers/compass_hmc5883l.h"
|
#include "drivers/compass_hmc5883l.h"
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "flight/flight.h"
|
#include "flight/flight.h"
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
#include "sensors/sonar.h"
|
#include "sensors/sonar.h"
|
||||||
|
|
||||||
|
|
||||||
// Use these to help with porting to new boards
|
// Use these to help with porting to new boards
|
||||||
//#define USE_FAKE_GYRO
|
//#define USE_FAKE_GYRO
|
||||||
#define USE_GYRO_L3G4200D
|
#define USE_GYRO_L3G4200D
|
||||||
#define USE_GYRO_L3GD20
|
#define USE_GYRO_L3GD20
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define USE_GYRO_MPU3050
|
#define USE_GYRO_MPU3050
|
||||||
//#define USE_FAKE_ACC
|
//#define USE_FAKE_ACC
|
||||||
#define USE_ACC_ADXL345
|
#define USE_ACC_ADXL345
|
||||||
#define USE_ACC_BMA280
|
#define USE_ACC_BMA280
|
||||||
#define USE_ACC_MMA8452
|
#define USE_ACC_MMA8452
|
||||||
#define USE_ACC_LSM303DLHC
|
#define USE_ACC_LSM303DLHC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
#define USE_BARO_BMP085
|
#define USE_BARO_BMP085
|
||||||
|
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
#undef USE_ACC_LSM303DLHC
|
#undef USE_ACC_LSM303DLHC
|
||||||
#undef USE_ACC_SPI_MPU6000
|
#undef USE_ACC_SPI_MPU6000
|
||||||
#undef USE_GYRO_SPI_MPU6000
|
#undef USE_GYRO_SPI_MPU6000
|
||||||
#undef USE_GYRO_L3GD20
|
#undef USE_GYRO_L3GD20
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef NAZE32PRO
|
#ifdef NAZE32PRO
|
||||||
#define USE_FAKE_ACC
|
#define USE_FAKE_ACC
|
||||||
#define USE_FAKE_GYRO
|
#define USE_FAKE_GYRO
|
||||||
#undef USE_ACC_LSM303DLHC
|
#undef USE_ACC_LSM303DLHC
|
||||||
#undef USE_ACC_ADXL345
|
#undef USE_ACC_ADXL345
|
||||||
#undef USE_ACC_BMA280
|
#undef USE_ACC_BMA280
|
||||||
#undef USE_ACC_MMA8452
|
#undef USE_ACC_MMA8452
|
||||||
#undef USE_ACC_LSM303DLHC
|
#undef USE_ACC_LSM303DLHC
|
||||||
#undef USE_ACC_MPU6050
|
#undef USE_ACC_MPU6050
|
||||||
#undef USE_ACC_SPI_MPU6000
|
#undef USE_ACC_SPI_MPU6000
|
||||||
#undef USE_GYRO_L3G4200D
|
#undef USE_GYRO_L3G4200D
|
||||||
#undef USE_GYRO_L3GD20
|
#undef USE_GYRO_L3GD20
|
||||||
#undef USE_GYRO_MPU3050
|
#undef USE_GYRO_MPU3050
|
||||||
#undef USE_GYRO_MPU6050
|
#undef USE_GYRO_MPU6050
|
||||||
#undef USE_GYRO_SPI_MPU6000
|
#undef USE_GYRO_SPI_MPU6000
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(OLIMEXINO) || defined(EUSTM32F103RC)
|
#if defined(OLIMEXINO) || defined(EUSTM32F103RC)
|
||||||
#undef USE_GYRO_L3GD20
|
#undef USE_GYRO_L3GD20
|
||||||
#undef USE_GYRO_L3G4200D
|
#undef USE_GYRO_L3G4200D
|
||||||
#undef USE_GYRO_MPU3050
|
#undef USE_GYRO_MPU3050
|
||||||
#undef USE_GYRO_SPI_MPU6000
|
#undef USE_GYRO_SPI_MPU6000
|
||||||
#undef USE_ACC_LSM303DLHC
|
#undef USE_ACC_LSM303DLHC
|
||||||
#undef USE_ACC_BMA280
|
#undef USE_ACC_BMA280
|
||||||
#undef USE_ACC_MMA8452
|
#undef USE_ACC_MMA8452
|
||||||
#undef USE_ACC_ADXL345
|
#undef USE_ACC_ADXL345
|
||||||
#undef USE_ACC_SPI_MPU6000
|
#undef USE_ACC_SPI_MPU6000
|
||||||
#undef USE_BARO_MS5611
|
#undef USE_BARO_MS5611
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef EUSTM32F103RC
|
#ifdef EUSTM32F103RC
|
||||||
#define USE_FAKE_GYRO
|
#define USE_FAKE_GYRO
|
||||||
#define USE_FAKE_ACC
|
#define USE_FAKE_ACC
|
||||||
#define USE_GYRO_L3G4200D
|
#define USE_GYRO_L3G4200D
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef STM32F3DISCOVERY
|
#ifdef STM32F3DISCOVERY
|
||||||
#undef USE_ACC_SPI_MPU6000
|
#undef USE_ACC_SPI_MPU6000
|
||||||
#undef USE_GYRO_SPI_MPU6000
|
#undef USE_GYRO_SPI_MPU6000
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CHEBUZZF3
|
#ifdef CHEBUZZF3
|
||||||
#undef USE_GYRO_L3G4200D
|
#undef USE_GYRO_L3G4200D
|
||||||
#undef USE_GYRO_MPU6050
|
#undef USE_GYRO_MPU6050
|
||||||
#undef USE_GYRO_MPU3050
|
#undef USE_GYRO_MPU3050
|
||||||
#undef USE_GYRO_SPI_MPU6000
|
#undef USE_GYRO_SPI_MPU6000
|
||||||
#undef USE_ACC_ADXL345
|
#undef USE_ACC_ADXL345
|
||||||
#undef USE_ACC_BMA280
|
#undef USE_ACC_BMA280
|
||||||
#undef USE_ACC_MPU6050
|
#undef USE_ACC_MPU6050
|
||||||
#undef USE_ACC_MMA8452
|
#undef USE_ACC_MMA8452
|
||||||
#undef USE_ACC_SPI_MPU6000
|
#undef USE_ACC_SPI_MPU6000
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
#undef USE_GYRO_L3GD20
|
#undef USE_GYRO_L3GD20
|
||||||
#undef USE_GYRO_L3G4200D
|
#undef USE_GYRO_L3G4200D
|
||||||
#undef USE_GYRO_MPU6050
|
#undef USE_GYRO_MPU6050
|
||||||
#undef USE_GYRO_MPU3050
|
#undef USE_GYRO_MPU3050
|
||||||
#undef USE_ACC_LSM303DLHC
|
#undef USE_ACC_LSM303DLHC
|
||||||
#undef USE_ACC_ADXL345
|
#undef USE_ACC_ADXL345
|
||||||
#undef USE_ACC_BMA280
|
#undef USE_ACC_BMA280
|
||||||
#undef USE_ACC_MPU6050
|
#undef USE_ACC_MPU6050
|
||||||
#undef USE_ACC_MMA8452
|
#undef USE_ACC_MMA8452
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CJMCU
|
#ifdef CJMCU
|
||||||
#undef USE_GYRO_SPI_MPU6000
|
#undef USE_GYRO_SPI_MPU6000
|
||||||
#undef USE_GYRO_L3GD20
|
#undef USE_GYRO_L3GD20
|
||||||
#undef USE_GYRO_L3G4200D
|
#undef USE_GYRO_L3G4200D
|
||||||
#undef USE_GYRO_MPU3050
|
#undef USE_GYRO_MPU3050
|
||||||
#undef USE_ACC_LSM303DLHC
|
#undef USE_ACC_LSM303DLHC
|
||||||
#undef USE_ACC_SPI_MPU6000
|
#undef USE_ACC_SPI_MPU6000
|
||||||
#undef USE_ACC_ADXL345
|
#undef USE_ACC_ADXL345
|
||||||
#undef USE_ACC_BMA280
|
#undef USE_ACC_BMA280
|
||||||
#undef USE_ACC_MMA8452
|
#undef USE_ACC_MMA8452
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern float magneticDeclination;
|
extern float magneticDeclination;
|
||||||
|
|
||||||
extern gyro_t gyro;
|
extern gyro_t gyro;
|
||||||
extern baro_t baro;
|
extern baro_t baro;
|
||||||
extern acc_t acc;
|
extern acc_t acc;
|
||||||
|
|
||||||
#ifdef USE_FAKE_GYRO
|
#ifdef USE_FAKE_GYRO
|
||||||
static void fakeGyroInit(void) {}
|
static void fakeGyroInit(void) {}
|
||||||
static void fakeGyroRead(int16_t *gyroData) {
|
static void fakeGyroRead(int16_t *gyroData) {
|
||||||
UNUSED(gyroData);
|
UNUSED(gyroData);
|
||||||
}
|
}
|
||||||
static void fakeGyroReadTemp(int16_t *tempData) {
|
static void fakeGyroReadTemp(int16_t *tempData) {
|
||||||
UNUSED(tempData);
|
UNUSED(tempData);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool fakeGyroDetect(gyro_t *gyro, uint16_t lpf)
|
bool fakeGyroDetect(gyro_t *gyro, uint16_t lpf)
|
||||||
{
|
{
|
||||||
UNUSED(lpf);
|
UNUSED(lpf);
|
||||||
gyro->init = fakeGyroInit;
|
gyro->init = fakeGyroInit;
|
||||||
gyro->read = fakeGyroRead;
|
gyro->read = fakeGyroRead;
|
||||||
gyro->temperature = fakeGyroReadTemp;
|
gyro->temperature = fakeGyroReadTemp;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FAKE_ACC
|
#ifdef USE_FAKE_ACC
|
||||||
static void fakeAccInit(void) {}
|
static void fakeAccInit(void) {}
|
||||||
static void fakeAccRead(int16_t *accData) {
|
static void fakeAccRead(int16_t *accData) {
|
||||||
UNUSED(accData);
|
UNUSED(accData);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool fakeAccDetect(acc_t *acc)
|
bool fakeAccDetect(acc_t *acc)
|
||||||
{
|
{
|
||||||
acc->init = fakeAccInit;
|
acc->init = fakeAccInit;
|
||||||
acc->read = fakeAccRead;
|
acc->read = fakeAccRead;
|
||||||
acc->revisionCode = 0;
|
acc->revisionCode = 0;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
bool detectGyro(uint16_t gyroLpf)
|
bool detectGyro(uint16_t gyroLpf)
|
||||||
{
|
{
|
||||||
gyroAlign = ALIGN_DEFAULT;
|
gyroAlign = ALIGN_DEFAULT;
|
||||||
|
|
||||||
#ifdef USE_GYRO_MPU6050
|
#ifdef USE_GYRO_MPU6050
|
||||||
if (mpu6050GyroDetect(&gyro, gyroLpf)) {
|
if (mpu6050GyroDetect(&gyro, gyroLpf)) {
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
gyroAlign = CW0_DEG;
|
gyroAlign = CW0_DEG;
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_GYRO_L3G4200D
|
#ifdef USE_GYRO_L3G4200D
|
||||||
if (l3g4200dDetect(&gyro, gyroLpf)) {
|
if (l3g4200dDetect(&gyro, gyroLpf)) {
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
gyroAlign = CW0_DEG;
|
gyroAlign = CW0_DEG;
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_GYRO_MPU3050
|
#ifdef USE_GYRO_MPU3050
|
||||||
if (mpu3050Detect(&gyro, gyroLpf)) {
|
if (mpu3050Detect(&gyro, gyroLpf)) {
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
gyroAlign = CW0_DEG;
|
gyroAlign = CW0_DEG;
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_GYRO_L3GD20
|
#ifdef USE_GYRO_L3GD20
|
||||||
if (l3gd20Detect(&gyro, gyroLpf)) {
|
if (l3gd20Detect(&gyro, gyroLpf)) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_GYRO_SPI_MPU6000
|
#ifdef USE_GYRO_SPI_MPU6000
|
||||||
if (mpu6000SpiGyroDetect(&gyro, gyroLpf)) {
|
if (mpu6000SpiGyroDetect(&gyro, gyroLpf)) {
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
gyroAlign = CW270_DEG;
|
gyroAlign = CW270_DEG;
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FAKE_GYRO
|
#ifdef USE_FAKE_GYRO
|
||||||
if (fakeGyroDetect(&gyro, gyroLpf)) {
|
if (fakeGyroDetect(&gyro, gyroLpf)) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void detectAcc(uint8_t accHardwareToUse)
|
static void detectAcc(uint8_t accHardwareToUse)
|
||||||
{
|
{
|
||||||
#ifdef USE_ACC_ADXL345
|
#ifdef USE_ACC_ADXL345
|
||||||
drv_adxl345_config_t acc_params;
|
drv_adxl345_config_t acc_params;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
retry:
|
retry:
|
||||||
accAlign = ALIGN_DEFAULT;
|
accAlign = ALIGN_DEFAULT;
|
||||||
|
|
||||||
switch (accHardwareToUse) {
|
switch (accHardwareToUse) {
|
||||||
#ifdef USE_FAKE_ACC
|
#ifdef USE_FAKE_ACC
|
||||||
default:
|
default:
|
||||||
if (fakeAccDetect(&acc)) {
|
if (fakeAccDetect(&acc)) {
|
||||||
accHardware = ACC_FAKE;
|
accHardware = ACC_FAKE;
|
||||||
if (accHardwareToUse == ACC_FAKE)
|
if (accHardwareToUse == ACC_FAKE)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
case ACC_NONE: // disable ACC
|
case ACC_NONE: // disable ACC
|
||||||
sensorsClear(SENSOR_ACC);
|
sensorsClear(SENSOR_ACC);
|
||||||
break;
|
break;
|
||||||
case ACC_DEFAULT: // autodetect
|
case ACC_DEFAULT: // autodetect
|
||||||
#ifdef USE_ACC_ADXL345
|
#ifdef USE_ACC_ADXL345
|
||||||
case ACC_ADXL345: // ADXL345
|
case ACC_ADXL345: // ADXL345
|
||||||
acc_params.useFifo = false;
|
acc_params.useFifo = false;
|
||||||
acc_params.dataRate = 800; // unused currently
|
acc_params.dataRate = 800; // unused currently
|
||||||
if (adxl345Detect(&acc_params, &acc)) {
|
if (adxl345Detect(&acc_params, &acc)) {
|
||||||
accHardware = ACC_ADXL345;
|
accHardware = ACC_ADXL345;
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
accAlign = CW270_DEG;
|
accAlign = CW270_DEG;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
if (accHardwareToUse == ACC_ADXL345)
|
if (accHardwareToUse == ACC_ADXL345)
|
||||||
break;
|
break;
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ACC_MPU6050
|
#ifdef USE_ACC_MPU6050
|
||||||
case ACC_MPU6050: // MPU6050
|
case ACC_MPU6050: // MPU6050
|
||||||
if (mpu6050AccDetect(&acc)) {
|
if (mpu6050AccDetect(&acc)) {
|
||||||
accHardware = ACC_MPU6050;
|
accHardware = ACC_MPU6050;
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
accAlign = CW0_DEG;
|
accAlign = CW0_DEG;
|
||||||
#endif
|
#endif
|
||||||
if (accHardwareToUse == ACC_MPU6050)
|
if (accHardwareToUse == ACC_MPU6050)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ACC_MMA8452
|
#ifdef USE_ACC_MMA8452
|
||||||
case ACC_MMA8452: // MMA8452
|
case ACC_MMA8452: // MMA8452
|
||||||
if (mma8452Detect(&acc)) {
|
if (mma8452Detect(&acc)) {
|
||||||
accHardware = ACC_MMA8452;
|
accHardware = ACC_MMA8452;
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
accAlign = CW90_DEG;
|
accAlign = CW90_DEG;
|
||||||
#endif
|
#endif
|
||||||
if (accHardwareToUse == ACC_MMA8452)
|
if (accHardwareToUse == ACC_MMA8452)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ACC_BMA280
|
#ifdef USE_ACC_BMA280
|
||||||
case ACC_BMA280: // BMA280
|
case ACC_BMA280: // BMA280
|
||||||
if (bma280Detect(&acc)) {
|
if (bma280Detect(&acc)) {
|
||||||
accHardware = ACC_BMA280;
|
accHardware = ACC_BMA280;
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
accAlign = CW0_DEG;
|
accAlign = CW0_DEG;
|
||||||
#endif
|
#endif
|
||||||
if (accHardwareToUse == ACC_BMA280)
|
if (accHardwareToUse == ACC_BMA280)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ACC_LSM303DLHC
|
#ifdef USE_ACC_LSM303DLHC
|
||||||
case ACC_LSM303DLHC:
|
case ACC_LSM303DLHC:
|
||||||
if (lsm303dlhcAccDetect(&acc)) {
|
if (lsm303dlhcAccDetect(&acc)) {
|
||||||
accHardware = ACC_LSM303DLHC;
|
accHardware = ACC_LSM303DLHC;
|
||||||
if (accHardwareToUse == ACC_LSM303DLHC)
|
if (accHardwareToUse == ACC_LSM303DLHC)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_GYRO_SPI_MPU6000
|
#ifdef USE_GYRO_SPI_MPU6000
|
||||||
case ACC_SPI_MPU6000:
|
case ACC_SPI_MPU6000:
|
||||||
if (mpu6000SpiAccDetect(&acc)) {
|
if (mpu6000SpiAccDetect(&acc)) {
|
||||||
accHardware = ACC_SPI_MPU6000;
|
accHardware = ACC_SPI_MPU6000;
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
accAlign = CW270_DEG;
|
accAlign = CW270_DEG;
|
||||||
#endif
|
#endif
|
||||||
if (accHardwareToUse == ACC_SPI_MPU6000)
|
if (accHardwareToUse == ACC_SPI_MPU6000)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#endif
|
#endif
|
||||||
; // prevent compiler error
|
; // prevent compiler error
|
||||||
}
|
}
|
||||||
|
|
||||||
// Found anything? Check if user fucked up or ACC is really missing.
|
// Found anything? Check if user fucked up or ACC is really missing.
|
||||||
if (accHardware == ACC_DEFAULT) {
|
if (accHardware == ACC_DEFAULT) {
|
||||||
if (accHardwareToUse > ACC_DEFAULT) {
|
if (accHardwareToUse > ACC_DEFAULT) {
|
||||||
// Nothing was found and we have a forced sensor type. Stupid user probably chose a sensor that isn't present.
|
// Nothing was found and we have a forced sensor type. Stupid user probably chose a sensor that isn't present.
|
||||||
accHardwareToUse = ACC_DEFAULT;
|
accHardwareToUse = ACC_DEFAULT;
|
||||||
goto retry;
|
goto retry;
|
||||||
} else {
|
} else {
|
||||||
// No ACC was detected
|
// No ACC was detected
|
||||||
sensorsClear(SENSOR_ACC);
|
sensorsClear(SENSOR_ACC);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void detectBaro()
|
static void detectBaro()
|
||||||
{
|
{
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
#ifdef USE_BARO_MS5611
|
#ifdef USE_BARO_MS5611
|
||||||
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
||||||
if (ms5611Detect(&baro)) {
|
if (ms5611Detect(&baro)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_BARO_BMP085
|
#ifdef USE_BARO_BMP085
|
||||||
// ms5611 disables BMP085, and tries to initialize + check PROM crc. if this works, we have a baro
|
// ms5611 disables BMP085, and tries to initialize + check PROM crc. if this works, we have a baro
|
||||||
if (bmp085Detect(&baro)) {
|
if (bmp085Detect(&baro)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
sensorsClear(SENSOR_BARO);
|
sensorsClear(SENSOR_BARO);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
|
void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
|
||||||
{
|
{
|
||||||
if (sensorAlignmentConfig->gyro_align != ALIGN_DEFAULT) {
|
if (sensorAlignmentConfig->gyro_align != ALIGN_DEFAULT) {
|
||||||
gyroAlign = sensorAlignmentConfig->gyro_align;
|
gyroAlign = sensorAlignmentConfig->gyro_align;
|
||||||
}
|
}
|
||||||
if (sensorAlignmentConfig->acc_align != ALIGN_DEFAULT) {
|
if (sensorAlignmentConfig->acc_align != ALIGN_DEFAULT) {
|
||||||
accAlign = sensorAlignmentConfig->acc_align;
|
accAlign = sensorAlignmentConfig->acc_align;
|
||||||
}
|
}
|
||||||
if (sensorAlignmentConfig->mag_align != ALIGN_DEFAULT) {
|
if (sensorAlignmentConfig->mag_align != ALIGN_DEFAULT) {
|
||||||
magAlign = sensorAlignmentConfig->mag_align;
|
magAlign = sensorAlignmentConfig->mag_align;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig)
|
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig)
|
||||||
{
|
{
|
||||||
int16_t deg, min;
|
int16_t deg, min;
|
||||||
memset(&acc, sizeof(acc), 0);
|
memset(&acc, sizeof(acc), 0);
|
||||||
memset(&gyro, sizeof(gyro), 0);
|
memset(&gyro, sizeof(gyro), 0);
|
||||||
|
|
||||||
if (!detectGyro(gyroLpf)) {
|
if (!detectGyro(gyroLpf)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
detectAcc(accHardwareToUse);
|
detectAcc(accHardwareToUse);
|
||||||
detectBaro();
|
detectBaro();
|
||||||
|
|
||||||
reconfigureAlignment(sensorAlignmentConfig);
|
reconfigureAlignment(sensorAlignmentConfig);
|
||||||
|
|
||||||
// Now time to init things, acc first
|
// Now time to init things, acc first
|
||||||
if (sensors(SENSOR_ACC))
|
if (sensors(SENSOR_ACC))
|
||||||
acc.init();
|
acc.init();
|
||||||
// this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here.
|
// this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here.
|
||||||
gyro.init();
|
gyro.init();
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef MAG
|
||||||
if (hmc5883lDetect()) {
|
if (hmc5883lDetect()) {
|
||||||
magAlign = CW180_DEG; // default NAZE alignment
|
magAlign = CW180_DEG; // default NAZE alignment
|
||||||
} else {
|
} else {
|
||||||
sensorsClear(SENSOR_MAG);
|
sensorsClear(SENSOR_MAG);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
|
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
// calculate magnetic declination
|
// calculate magnetic declination
|
||||||
deg = magDeclinationFromConfig / 100;
|
deg = magDeclinationFromConfig / 100;
|
||||||
min = magDeclinationFromConfig % 100;
|
min = magDeclinationFromConfig % 100;
|
||||||
|
|
||||||
magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
|
magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
|
||||||
} else {
|
} else {
|
||||||
magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.
|
magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,72 +1,72 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define LED0_GPIO GPIOB
|
#define LED0_GPIO GPIOB
|
||||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||||
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||||
#define LED1_GPIO GPIOB
|
#define LED1_GPIO GPIOB
|
||||||
#define LED1_PIN Pin_4 // PB4 (LED)
|
#define LED1_PIN Pin_4 // PB4 (LED)
|
||||||
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
|
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||||
|
|
||||||
|
|
||||||
#define BEEP_GPIO GPIOA
|
#define BEEP_GPIO GPIOA
|
||||||
#define BEEP_PIN Pin_12 // PA12 (Beeper)
|
#define BEEP_PIN Pin_12 // PA12 (Beeper)
|
||||||
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||||
|
|
||||||
#define BARO_GPIO GPIOC
|
#define BARO_GPIO GPIOC
|
||||||
#define BARO_PIN Pin_13
|
#define BARO_PIN Pin_13
|
||||||
|
|
||||||
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
|
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||||
#define INVERTER_GPIO GPIOB
|
#define INVERTER_GPIO GPIOB
|
||||||
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
|
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||||
#define INVERTER_USART USART2
|
#define INVERTER_USART USART2
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define ACC
|
#define ACC
|
||||||
#define MAG
|
#define MAG
|
||||||
#define BARO
|
#define BARO
|
||||||
#define SONAR
|
#define SONAR
|
||||||
#define BEEPER
|
#define BEEPER
|
||||||
#define LED0
|
#define LED0
|
||||||
#define LED1
|
#define LED1
|
||||||
#define INVERTER
|
#define INVERTER
|
||||||
#define DISPLAY
|
#define DISPLAY
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
#define USE_USART2
|
#define USE_USART2
|
||||||
#define USE_SOFT_SERIAL
|
#define USE_SOFT_SERIAL
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
|
|
||||||
|
|
||||||
#define I2C_DEVICE (I2CDEV_2)
|
#define I2C_DEVICE (I2CDEV_2)
|
||||||
|
|
||||||
// #define SOFT_I2C // enable to test software i2c
|
// #define SOFT_I2C // enable to test software i2c
|
||||||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||||
// #define SOFT_I2C_PB67
|
// #define SOFT_I2C_PB67
|
||||||
|
|
||||||
|
|
||||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||||
|
|
||||||
#define GPS
|
#define GPS
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define TELEMETRY
|
#define TELEMETRY
|
||||||
#define SOFT_SERIAL
|
#define SOFT_SERIAL
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
#define AUTOTUNE
|
#define AUTOTUNE
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue