1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 01:35:35 +03:00

Make CW270FLIP default MAG alignment, drop per-MAG alignment and convert per-board to config level

This commit is contained in:
Pawel Spychalski (DzikuVx) 2021-05-06 12:28:14 +02:00
parent 55697421b9
commit 9450f1bb8b
44 changed files with 207 additions and 89 deletions

View file

@ -301,6 +301,12 @@ void validateAndFixConfig(void)
// Call target-specific validation function // Call target-specific validation function
validateAndFixTargetConfig(); validateAndFixTargetConfig();
#ifdef USE_MAG
if (compassConfig()->mag_align == ALIGN_DEFAULT) {
compassConfigMutable()->mag_align = CW270_DEG_FLIP;
}
#endif
if (settingsValidate(NULL)) { if (settingsValidate(NULL)) {
DISABLE_ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING); DISABLE_ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING);
} else { } else {

View file

@ -95,9 +95,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_QMC5883: case MAG_QMC5883:
#ifdef USE_MAG_QMC5883 #ifdef USE_MAG_QMC5883
if (qmc5883Detect(dev)) { if (qmc5883Detect(dev)) {
#ifdef MAG_QMC5883_ALIGN
dev->magAlign.onBoard = MAG_QMC5883_ALIGN;
#endif
magHardware = MAG_QMC5883; magHardware = MAG_QMC5883;
break; break;
} }
@ -111,9 +108,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_HMC5883: case MAG_HMC5883:
#ifdef USE_MAG_HMC5883 #ifdef USE_MAG_HMC5883
if (hmc5883lDetect(dev)) { if (hmc5883lDetect(dev)) {
#ifdef MAG_HMC5883_ALIGN
dev->magAlign.onBoard = MAG_HMC5883_ALIGN;
#endif
magHardware = MAG_HMC5883; magHardware = MAG_HMC5883;
break; break;
} }
@ -127,9 +121,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_AK8975: case MAG_AK8975:
#ifdef USE_MAG_AK8975 #ifdef USE_MAG_AK8975
if (ak8975Detect(dev)) { if (ak8975Detect(dev)) {
#ifdef MAG_AK8975_ALIGN
dev->magAlign.onBoard = MAG_AK8975_ALIGN;
#endif
magHardware = MAG_AK8975; magHardware = MAG_AK8975;
break; break;
} }
@ -143,9 +134,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_AK8963: case MAG_AK8963:
#ifdef USE_MAG_AK8963 #ifdef USE_MAG_AK8963
if (ak8963Detect(dev)) { if (ak8963Detect(dev)) {
#ifdef MAG_AK8963_ALIGN
dev->magAlign.onBoard = MAG_AK8963_ALIGN;
#endif
magHardware = MAG_AK8963; magHardware = MAG_AK8963;
break; break;
} }
@ -159,9 +147,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_GPS: case MAG_GPS:
#ifdef USE_GPS #ifdef USE_GPS
if (gpsMagDetect(dev)) { if (gpsMagDetect(dev)) {
#ifdef MAG_GPS_ALIGN
dev->magAlign.onBoard = MAG_GPS_ALIGN;
#endif
magHardware = MAG_GPS; magHardware = MAG_GPS;
break; break;
} }
@ -175,9 +160,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_MAG3110: case MAG_MAG3110:
#ifdef USE_MAG_MAG3110 #ifdef USE_MAG_MAG3110
if (mag3110detect(dev)) { if (mag3110detect(dev)) {
#ifdef MAG_MAG3110_ALIGN
dev->magAlign.onBoard = MAG_MAG3110_ALIGN;
#endif
magHardware = MAG_MAG3110; magHardware = MAG_MAG3110;
break; break;
} }
@ -191,9 +173,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_IST8310: case MAG_IST8310:
#ifdef USE_MAG_IST8310 #ifdef USE_MAG_IST8310
if (ist8310Detect(dev)) { if (ist8310Detect(dev)) {
#ifdef MAG_IST8310_ALIGN
dev->magAlign.onBoard = MAG_IST8310_ALIGN;
#endif
magHardware = MAG_IST8310; magHardware = MAG_IST8310;
break; break;
} }
@ -207,9 +186,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_IST8308: case MAG_IST8308:
#ifdef USE_MAG_IST8308 #ifdef USE_MAG_IST8308
if (ist8308Detect(dev)) { if (ist8308Detect(dev)) {
#ifdef MAG_IST8308_ALIGN
dev->magAlign.onBoard = MAG_IST8308_ALIGN;
#endif
magHardware = MAG_IST8308; magHardware = MAG_IST8308;
break; break;
} }
@ -223,9 +199,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_MPU9250: case MAG_MPU9250:
#ifdef USE_MAG_MPU9250 #ifdef USE_MAG_MPU9250
if (mpu9250CompassDetect(dev)) { if (mpu9250CompassDetect(dev)) {
#ifdef MAG_MPU9250_ALIGN
dev->magAlign.onBoard = MAG_MPU9250_ALIGN;
#endif
magHardware = MAG_MPU9250; magHardware = MAG_MPU9250;
break; break;
} }
@ -235,9 +208,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_LIS3MDL: case MAG_LIS3MDL:
#ifdef USE_MAG_LIS3MDL #ifdef USE_MAG_LIS3MDL
if (lis3mdlDetect(dev)) { if (lis3mdlDetect(dev)) {
#ifdef MAG_LIS3MDL_ALIGN
dev->magAlign = MAG_LIS3MDL_ALIGN;
#endif
magHardware = MAG_LIS3MDL; magHardware = MAG_LIS3MDL;
break; break;
} }
@ -266,9 +236,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
case MAG_RM3100: case MAG_RM3100:
#ifdef USE_MAG_RM3100 #ifdef USE_MAG_RM3100
if (rm3100MagDetect(dev)) { if (rm3100MagDetect(dev)) {
#ifdef MAG_RM3100_ALIGN
dev->magAlign.onBoard = MAG_RM3100_ALIGN;
#endif
magHardware = MAG_RM3100; magHardware = MAG_RM3100;
break; break;
} }
@ -344,6 +311,8 @@ bool compassInit(void)
mag.dev.magAlign.useExternal = false; mag.dev.magAlign.useExternal = false;
if (compassConfig()->mag_align != ALIGN_DEFAULT) { if (compassConfig()->mag_align != ALIGN_DEFAULT) {
mag.dev.magAlign.onBoard = compassConfig()->mag_align; mag.dev.magAlign.onBoard = compassConfig()->mag_align;
} else {
mag.dev.magAlign.onBoard = CW270_DEG_FLIP; // The most popular default is 270FLIP for external mags
} }
} }

View file

@ -46,7 +46,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_AK8963 #define USE_MAG_AK8963
#define USE_MAG_AK8975 #define USE_MAG_AK8975
@ -128,8 +127,6 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define MAG_GPS_ALIGN CW180_DEG_FLIP
#define DEFAULT_RX_TYPE RX_TYPE_PPM #define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DISABLE_RX_PWM_FEATURE #define DISABLE_RX_PWM_FEATURE
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT) #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT)

View file

@ -60,7 +60,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_MPU9250 #define USE_MAG_MPU9250
#define MAG_MPU9250_ALIGN CW0_DEG
#define USE_MAG_AK8963 #define USE_MAG_AK8963
#define USE_MAG_AK8975 #define USE_MAG_AK8975
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883

View file

@ -45,6 +45,7 @@
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "sensors/compass.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
@ -56,6 +57,8 @@
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(void) void targetConfiguration(void)
{ {
compassConfigMutable()->mag_align = CW90_DEG;
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
batteryMetersConfigMutable()->current.offset = CURRENTOFFSET; batteryMetersConfigMutable()->current.offset = CURRENTOFFSET;
batteryMetersConfigMutable()->current.scale = CURRENTSCALE; batteryMetersConfigMutable()->current.scale = CURRENTSCALE;

View file

@ -61,8 +61,6 @@
#define USE_MAG_IST8308 #define USE_MAG_IST8308
#define USE_MAG_LIS3MDL #define USE_MAG_LIS3MDL
#define MAG_MPU9250_ALIGN CW0_DEG
#define TEMPERATURE_I2C_BUS BUS_I2C1 #define TEMPERATURE_I2C_BUS BUS_I2C1
#define BNO055_I2C_BUS BUS_I2C1 #define BNO055_I2C_BUS BUS_I2C1

View file

@ -47,6 +47,7 @@
#include "config/feature.h" #include "config/feature.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/compass.h"
#include "hardware_revision.h" #include "hardware_revision.h"
@ -58,6 +59,8 @@
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(void) void targetConfiguration(void)
{ {
compassConfigMutable()->mag_align = CW90_DEG;
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
batteryMetersConfigMutable()->current.offset = CURRENTOFFSET; batteryMetersConfigMutable()->current.offset = CURRENTOFFSET;
batteryMetersConfigMutable()->current.scale = CURRENTSCALE; batteryMetersConfigMutable()->current.scale = CURRENTSCALE;

View file

@ -59,9 +59,6 @@
#define USE_MAG_IST8308 #define USE_MAG_IST8308
#define USE_MAG_LIS3MDL #define USE_MAG_LIS3MDL
#define MAG_AK9863_ALIGN CW0_DEG
#define MAG_MPU9250_ALIGN CW0_DEG
#define AK8963_CS_PIN PC15 #define AK8963_CS_PIN PC15
#define AK8963_SPI_BUS BUS_SPI3 #define AK8963_SPI_BUS BUS_SPI3

View file

@ -47,7 +47,6 @@
#define USE_MAG_IST8310 #define USE_MAG_IST8310
#define USE_MAG_IST8308 #define USE_MAG_IST8308
#define USE_MAG_LIS3MDL #define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define TEMPERATURE_I2C_BUS BUS_I2C2 #define TEMPERATURE_I2C_BUS BUS_I2C2
@ -104,8 +103,6 @@
//#define HIL //#define HIL
#define MAG_GPS_ALIGN CW180_DEG_FLIP
#define USE_ADC #define USE_ADC
#define ADC_CHANNEL_1_PIN PC0 #define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC1 #define ADC_CHANNEL_2_PIN PC1

View file

@ -40,7 +40,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310
@ -142,8 +141,6 @@
#define USE_I2C_DEVICE_4 #define USE_I2C_DEVICE_4
#define USE_I2C_DEVICE_2 #define USE_I2C_DEVICE_2
#define MAG_GPS_ALIGN CW180_DEG_FLIP
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO) #define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define USE_NAV #define USE_NAV

View file

@ -40,7 +40,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310

View file

@ -45,7 +45,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_AK8963 #define USE_MAG_AK8963
#define USE_MAG_AK8975 #define USE_MAG_AK8975

View file

@ -119,7 +119,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
//#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_AK8963 #define USE_MAG_AK8963
#define USE_MAG_AK8975 #define USE_MAG_AK8975
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883

View file

@ -48,7 +48,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define USE_MAG_AK8975 #define USE_MAG_AK8975
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883

View file

@ -0,0 +1,57 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_output.h"
#include "drivers/serial.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "rx/rx.h"
#include "io/serial.h"
#include "telemetry/telemetry.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "sensors/battery.h"
#include "sensors/compass.h"
#include "hardware_revision.h"
void targetConfiguration(void)
{
compassConfigMutable()->mag_align = CW90_DEG;
}

View file

@ -52,7 +52,6 @@
#define USE_MAG #define USE_MAG
#define USE_MAG_MPU9250 #define USE_MAG_MPU9250
#define MAG_MPU9250_ALIGN CW90_DEG
// MPU6 interrupts // MPU6 interrupts
#define USE_EXTI #define USE_EXTI

View file

@ -20,18 +20,18 @@
#include "platform.h" #include "platform.h"
#include "config/feature.h" #include "config/feature.h"
#include "fc/config.h" #include "fc/config.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "io/serial.h" #include "io/serial.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "sensors/compass.h"
void targetConfiguration(void) void targetConfiguration(void)
{ {
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
rxConfigMutable()->receiverType = RX_TYPE_SERIAL; rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
#ifdef QUANTON
compassConfigMutable()->mag_align = CW90_DEG;
#endif
} }

View file

@ -60,10 +60,8 @@
#ifdef QUANTON #ifdef QUANTON
#define IMU_MPU6000_ALIGN CW90_DEG #define IMU_MPU6000_ALIGN CW90_DEG
#define MAG_HMC5883_ALIGN CW90_DEG
#else #else
#define IMU_MPU6000_ALIGN CW270_DEG_FLIP #define IMU_MPU6000_ALIGN CW270_DEG_FLIP
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#endif #endif
#define USE_BARO #define USE_BARO

32
src/main/target/F4BY/config.c Executable file
View file

@ -0,0 +1,32 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "config/feature.h"
#include "fc/config.h"
#include "flight/mixer.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "sensors/compass.h"
void targetConfiguration(void)
{
compassConfigMutable()->mag_align = CW90_DEG;
}

View file

@ -47,7 +47,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310

View file

@ -18,21 +18,16 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "config/config_master.h" #include "config/config_master.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "io/serial.h" #include "io/serial.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "sensors/compass.h"
// alternative defaults settings for FF_F35_LIGHTNING targets
void targetConfiguration(void) void targetConfiguration(void)
{ {
motorConfigMutable()->maxthrottle = 2000; compassConfigMutable()->mag_align = CW90_DEG;
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600;

View file

@ -42,7 +42,6 @@
#define USE_MAG #define USE_MAG
#define USE_MAG_MPU9250 #define USE_MAG_MPU9250
#define MAG_MPU9250_ALIGN CW90_DEG_FLIP
#define USE_BARO #define USE_BARO
#define USE_BARO_BMP280 #define USE_BARO_BMP280

View file

@ -60,7 +60,6 @@
#define USE_MAG_IST8308 #define USE_MAG_IST8308
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL #define USE_MAG_LIS3MDL
#define MAG_IST8310_ALIGN CW270_DEG
// *************** Temperature sensor ***************** // *************** Temperature sensor *****************
#define TEMPERATURE_I2C_BUS BUS_I2C1 #define TEMPERATURE_I2C_BUS BUS_I2C1

View file

@ -57,7 +57,6 @@
# define USE_MAG # define USE_MAG
# define MAG_I2C_BUS BUS_I2C1 # define MAG_I2C_BUS BUS_I2C1
# define USE_MAG_HMC5883 # define USE_MAG_HMC5883
# define MAG_HMC5883_ALIGN CW180_DEG
# define USE_MAG_QMC5883 # define USE_MAG_QMC5883
# define USE_MAG_MAG3110 # define USE_MAG_MAG3110
# define USE_MAG_IST8310 # define USE_MAG_IST8310

View file

@ -140,7 +140,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW180_DEG
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_MAG3110 #define USE_MAG_MAG3110
#define USE_MAG_IST8310 #define USE_MAG_IST8310

View file

@ -41,7 +41,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310

View file

@ -20,11 +20,12 @@
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"
#include "io/serial.h" #include "io/serial.h"
#include "sensors/compass.h"
void targetConfiguration(void) void targetConfiguration(void)
{ {
compassConfigMutable()->mag_align = CW0_DEG_FLIP;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_GPS; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_GPS;
// serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].gps_baudrateIndex = BAUD_115200; // serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].gps_baudrateIndex = BAUD_115200;

View file

@ -85,7 +85,6 @@
#define SPI2_MOSI_PIN PB15 #define SPI2_MOSI_PIN PB15
#define USE_MAG_RM3100 #define USE_MAG_RM3100
#define MAG_RM3100_ALIGN CW0_DEG_FLIP
#define RM3100_CS_PIN PB12 #define RM3100_CS_PIN PB12
#define RM3100_SPI_BUS BUS_SPI2 #define RM3100_SPI_BUS BUS_SPI2

View file

@ -90,7 +90,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS I2C_EXT_BUS #define MAG_I2C_BUS I2C_EXT_BUS
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310

View file

@ -149,7 +149,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310

View file

@ -0,0 +1,32 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "config/feature.h"
#include "fc/config.h"
#include "flight/mixer.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "sensors/compass.h"
void targetConfiguration(void)
{
compassConfigMutable()->mag_align = CW90_DEG;
}

View file

@ -44,7 +44,6 @@
#define USE_IMU_MPU9250 #define USE_IMU_MPU9250
#define IMU_MPU9250_ALIGN CW180_DEG_FLIP #define IMU_MPU9250_ALIGN CW180_DEG_FLIP
#define MAG_MPU9250_ALIGN CW90_DEG
#define USE_DUAL_GYRO #define USE_DUAL_GYRO

View file

@ -36,7 +36,6 @@
// #define USE_MAG // #define USE_MAG
// #define MAG_I2C_BUS BUS_I2C1 // #define MAG_I2C_BUS BUS_I2C1
// #define MAG_HMC5883_ALIGN CW90_DEG
// #define USE_MAG_HMC5883 // #define USE_MAG_HMC5883
// #define USE_MAG_QMC5883 // #define USE_MAG_QMC5883
// #define USE_MAG_IST8310 // #define USE_MAG_IST8310

32
src/main/target/REVO/config.c Executable file
View file

@ -0,0 +1,32 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "config/feature.h"
#include "fc/config.h"
#include "flight/mixer.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "sensors/compass.h"
void targetConfiguration(void)
{
compassConfigMutable()->mag_align = CW90_DEG;
}

View file

@ -47,7 +47,6 @@
#define USE_DUAL_MAG #define USE_DUAL_MAG
#define MAG_I2C_BUS_EXT BUS_I2C2 #define MAG_I2C_BUS_EXT BUS_I2C2
#define MAG_I2C_BUS_INT BUS_I2C1 #define MAG_I2C_BUS_INT BUS_I2C1
#define MAG_HMC5883_ALIGN CW90_DEG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310
@ -131,8 +130,6 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define MAG_GPS_ALIGN CW180_DEG_FLIP
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)

View file

@ -42,7 +42,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define MAG_AK8975_ALIGN CW0_DEG
#define USE_MAG_AK8975 #define USE_MAG_AK8975
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883

View file

@ -0,0 +1,32 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "config/feature.h"
#include "fc/config.h"
#include "flight/mixer.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "sensors/compass.h"
void targetConfiguration(void)
{
compassConfigMutable()->mag_align = CW0_DEG;
}

View file

@ -42,7 +42,6 @@
#define USE_MAG #define USE_MAG
#define USE_MAG_MPU9250 #define USE_MAG_MPU9250
#define MAG_MPU9250_ALIGN CW0_DEG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883

View file

@ -140,7 +140,6 @@
#define USE_MAG_IST8310 #define USE_MAG_IST8310
#define USE_MAG_MAG3110 #define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL #define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG
/*** ADC ***/ /*** ADC ***/
#define USE_ADC #define USE_ADC

View file

@ -42,7 +42,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define MAG_HMC5883_ALIGN CW270_DEG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_IST8310 #define USE_MAG_IST8310

View file

@ -47,7 +47,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define MAG_MPU9250_ALIGN CW270_DEG
#define USE_MAG_MPU9250 #define USE_MAG_MPU9250
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883

View file

@ -47,7 +47,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define MAG_AK8963_ALIGN CW270_DEG
#define USE_MAG_AK8963 #define USE_MAG_AK8963
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883

View file

@ -64,7 +64,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C2 #define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define TEMPERATURE_I2C_BUS BUS_I2C2 #define TEMPERATURE_I2C_BUS BUS_I2C2

View file

@ -44,7 +44,6 @@
#define USE_MAG #define USE_MAG
#define MAG_I2C_BUS BUS_I2C1 #define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define TEMPERATURE_I2C_BUS BUS_I2C1 #define TEMPERATURE_I2C_BUS BUS_I2C1
#define BNO055_I2C_BUS BUS_I2C1 #define BNO055_I2C_BUS BUS_I2C1