This commit is contained in:
jflyper 2016-12-09 00:09:25 +09:00
commit 0f59251b58
112 changed files with 1019 additions and 452 deletions

View File

@ -1271,9 +1271,9 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
gyroConfig()->gyro_soft_notch_cutoff_2);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(accelerometerConfig()->acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", sensorSelectionConfig()->acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", sensorSelectionConfig()->baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", sensorSelectionConfig()->mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", accelerometerConfig()->acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", barometerConfig()->baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", compassConfig()->mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", armingConfig()->gyro_cal_on_first_arm);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation:%d", rxConfig()->rcInterpolation);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", rxConfig()->rcInterpolationInterval);

View File

@ -27,7 +27,6 @@ typedef enum BlackboxDevice {
BLACKBOX_DEVICE_SDCARD = 2,
#endif
BLACKBOX_DEVICE_END
} BlackboxDevice;
typedef enum {

View File

@ -36,7 +36,7 @@ typedef enum {
typedef enum {
AI_ROLL = 0,
AI_PITCH,
AI_PITCH
} angle_index_t;
#define ANGLE_INDEX_COUNT 2

View File

@ -66,9 +66,6 @@
#define servoConfig(x) (&masterConfig.servoConfig)
#define servoMixerConfig(x) (&masterConfig.servoMixerConfig)
#define gimbalConfig(x) (&masterConfig.gimbalConfig)
#define sensorSelectionConfig(x) (&masterConfig.sensorSelectionConfig)
#define sensorAlignmentConfig(x) (&masterConfig.sensorAlignmentConfig)
#define sensorTrims(x) (&masterConfig.sensorTrims)
#define boardAlignment(x) (&masterConfig.boardAlignment)
#define imuConfig(x) (&masterConfig.imuConfig)
#define gyroConfig(x) (&masterConfig.gyroConfig)
@ -122,10 +119,6 @@ typedef struct master_s {
gimbalConfig_t gimbalConfig;
#endif
// global sensor-related stuff
sensorSelectionConfig_t sensorSelectionConfig;
sensorAlignmentConfig_t sensorAlignmentConfig;
sensorTrims_t sensorTrims;
boardAlignment_t boardAlignment;
imuConfig_t imuConfig;

View File

@ -22,7 +22,7 @@ typedef uint16_t pgn_t;
// parameter group registry flags
typedef enum {
PGRF_NONE = 0,
PGRF_CLASSIFICATON_BIT = (1 << 0),
PGRF_CLASSIFICATON_BIT = (1 << 0)
} pgRegistryFlags_e;
typedef enum {
@ -30,7 +30,7 @@ typedef enum {
PGR_PGN_VERSION_MASK = 0xf000,
PGR_SIZE_MASK = 0x0fff,
PGR_SIZE_SYSTEM_FLAG = 0x0000, // documentary
PGR_SIZE_PROFILE_FLAG = 0x8000, // start using flags from the top bit down
PGR_SIZE_PROFILE_FLAG = 0x8000 // start using flags from the top bit down
} pgRegistryInternal_e;
// function that resets a single parameter group instance

View File

@ -42,6 +42,7 @@ typedef struct gyroDev_s {
volatile bool dataReady;
uint16_t lpf;
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
sensor_align_e gyroAlign;
} gyroDev_t;
typedef struct accDev_s {
@ -49,4 +50,5 @@ typedef struct accDev_s {
sensorReadFuncPtr read; // read 3 axis data function
uint16_t acc_1G;
char revisionCode; // a revision code for the sensor, if known
sensor_align_e accAlign;
} accDev_t;

View File

@ -0,0 +1,110 @@
/*
* 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 "common/utils.h"
#include "accgyro.h"
#include "accgyro_fake.h"
#ifdef USE_FAKE_GYRO
static int16_t fakeGyroADC[XYZ_AXIS_COUNT];
static void fakeGyroInit(gyroDev_t *gyro)
{
UNUSED(gyro);
}
void fakeGyroSet(int16_t x, int16_t y, int16_t z)
{
fakeGyroADC[X] = x;
fakeGyroADC[Y] = y;
fakeGyroADC[Z] = z;
}
static bool fakeGyroRead(gyroDev_t *gyro)
{
gyro->gyroADCRaw[X] = fakeGyroADC[X];
gyro->gyroADCRaw[Y] = fakeGyroADC[Y];
gyro->gyroADCRaw[Z] = fakeGyroADC[Z];
return true;
}
static bool fakeGyroReadTemperature(int16_t *tempData)
{
UNUSED(tempData);
return true;
}
static bool fakeGyroInitStatus(gyroDev_t *gyro)
{
UNUSED(gyro);
return true;
}
bool fakeGyroDetect(gyroDev_t *gyro)
{
gyro->init = fakeGyroInit;
gyro->intStatus = fakeGyroInitStatus;
gyro->read = fakeGyroRead;
gyro->temperature = fakeGyroReadTemperature;
gyro->scale = 1.0f;
return true;
}
#endif // USE_FAKE_GYRO
#ifdef USE_FAKE_ACC
static int16_t fakeAccData[XYZ_AXIS_COUNT];
static void fakeAccInit(accDev_t *acc)
{
UNUSED(acc);
}
void fakeAccSet(int16_t x, int16_t y, int16_t z)
{
fakeAccData[X] = x;
fakeAccData[Y] = y;
fakeAccData[Z] = z;
}
static bool fakeAccRead(int16_t *accData)
{
accData[X] = fakeAccData[X];
accData[Y] = fakeAccData[Y];
accData[Z] = fakeAccData[Z];
return true;
}
bool fakeAccDetect(accDev_t *acc)
{
acc->init = fakeAccInit;
acc->read = fakeAccRead;
acc->revisionCode = 0;
return true;
}
#endif // USE_FAKE_ACC

View File

@ -0,0 +1,26 @@
/*
* 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/>.
*/
#pragma once
struct accDev_s;
bool fakeAccDetect(struct accDev_s *acc);
void fakeAccSet(int16_t x, int16_t y, int16_t z);
struct gyroDev_s;
bool fakeGyroDetect(struct gyroDev_s *gyro);
void fakeGyroSet(int16_t x, int16_t y, int16_t z);

View File

@ -24,11 +24,9 @@ typedef enum {
ADC_CURRENT = 1,
ADC_EXTERNAL1 = 2,
ADC_RSSI = 3,
ADC_CHANNEL_MAX = ADC_RSSI
ADC_CHANNEL_COUNT
} AdcChannel;
#define ADC_CHANNEL_COUNT (ADC_CHANNEL_MAX + 1)
typedef struct adc_config_s {
ioTag_t tag;
uint8_t adcChannel; // ADC1_INxx channel number

View File

@ -31,16 +31,9 @@
typedef enum ADCDevice {
ADCINVALID = -1,
ADCDEV_1 = 0,
#if defined(STM32F3)
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
ADCDEV_2,
ADCDEV_3,
ADCDEV_MAX = ADCDEV_3,
#elif defined(STM32F4) || defined(STM32F7)
ADCDEV_2,
ADCDEV_3,
ADCDEV_MAX = ADCDEV_3,
#else
ADCDEV_MAX = ADCDEV_1,
ADCDEV_3
#endif
} ADCDevice;

View File

@ -0,0 +1,70 @@
/*
* 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>
#ifdef USE_FAKE_BARO
#include "barometer.h"
#include "barometer_fake.h"
static int32_t fakePressure;
static int32_t fakeTemperature;
static void fakeBaroStartGet(void)
{
}
static void fakeBaroCalculate(int32_t *pressure, int32_t *temperature)
{
if (pressure)
*pressure = fakePressure;
if (temperature)
*temperature = fakeTemperature;
}
void fakeBaroSet(int32_t pressure, int32_t temperature)
{
fakePressure = pressure;
fakeTemperature = temperature;
}
bool fakeBaroDetect(baroDev_t *baro)
{
fakePressure = 101325; // pressure in Pa (0m MSL)
fakeTemperature = 2500; // temperature in 0.01 C = 25 deg
// these are dummy as temperature is measured as part of pressure
baro->ut_delay = 10000;
baro->get_ut = fakeBaroStartGet;
baro->start_ut = fakeBaroStartGet;
// only _up part is executed, and gets both temperature and pressure
baro->up_delay = 10000;
baro->start_up = fakeBaroStartGet;
baro->get_up = fakeBaroStartGet;
baro->calculate = fakeBaroCalculate;
return true;
}
#endif // USE_FAKE_BARO

View File

@ -0,0 +1,23 @@
/*
* 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/>.
*/
#pragma once
struct baroDev_s;
bool fakeBaroDetect(struct baroDev_s *baro);
void fakeBaroSet(int32_t pressure, int32_t temperature);

View File

@ -34,7 +34,7 @@ typedef enum I2CDevice {
I2CDEV_2,
I2CDEV_3,
I2CDEV_4,
I2CDEV_MAX = I2CDEV_4,
I2CDEV_COUNT
} I2CDevice;
typedef struct i2cDevice_s {

View File

@ -80,7 +80,7 @@ static i2cDevice_t i2cHardwareMap[] = {
typedef struct{
I2C_HandleTypeDef Handle;
}i2cHandle_t;
static i2cHandle_t i2cHandle[I2CDEV_MAX+1];
static i2cHandle_t i2cHandle[I2CDEV_COUNT];
void I2C1_ER_IRQHandler(void)
{

View File

@ -46,17 +46,17 @@ typedef enum {
SPI_CLOCK_SLOW = 128, //00.65625 MHz
SPI_CLOCK_STANDARD = 8, //10.50000 MHz
SPI_CLOCK_FAST = 4, //21.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //42.00000 MHz
SPI_CLOCK_ULTRAFAST = 2 //42.00000 MHz
#elif defined(STM32F7)
SPI_CLOCK_SLOW = 256, //00.42188 MHz
SPI_CLOCK_STANDARD = 16, //06.57500 MHz
SPI_CLOCK_FAST = 4, //27.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //54.00000 MHz
SPI_CLOCK_ULTRAFAST = 2 //54.00000 MHz
#else
SPI_CLOCK_SLOW = 128, //00.56250 MHz
SPI_CLOCK_STANDARD = 4, //09.00000 MHz
SPI_CLOCK_FAST = 2, //18.00000 MHz
SPI_CLOCK_ULTRAFAST = 2, //18.00000 MHz
SPI_CLOCK_ULTRAFAST = 2 //18.00000 MHz
#endif
} SPIClockDivider_e;
@ -65,8 +65,7 @@ typedef enum SPIDevice {
SPIDEV_1 = 0,
SPIDEV_2,
SPIDEV_3,
SPIDEV_4,
SPIDEV_MAX = SPIDEV_4,
SPIDEV_4
} SPIDevice;
typedef struct SPIDevice_s {

View File

@ -20,8 +20,7 @@
#include "io_types.h"
typedef enum softSPIDevice {
SOFT_SPIDEV_1 = 0,
SOFT_SPIDEV_MAX = SOFT_SPIDEV_1,
SOFT_SPIDEV_1 = 0
} softSPIDevice_e;
typedef struct softSPIDevice_s {

View File

@ -22,6 +22,7 @@
typedef struct magDev_s {
sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
sensor_align_e magAlign;
} magDev_t;
#ifndef MAG_I2C_INSTANCE

View File

@ -0,0 +1,66 @@
/*
* 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"
#ifdef USE_FAKE_MAG
#include "build/build_config.h"
#include "common/axis.h"
#include "compass.h"
#include "compass_fake.h"
static int16_t fakeMagData[XYZ_AXIS_COUNT];
static bool fakeMagInit(void)
{
// initially point north
fakeMagData[X] = 4096;
fakeMagData[Y] = 0;
fakeMagData[Z] = 0;
return true;
}
void fakeMagSet(int16_t x, int16_t y, int16_t z)
{
fakeMagData[X] = x;
fakeMagData[Y] = y;
fakeMagData[Z] = z;
}
static bool fakeMagRead(int16_t *magData)
{
magData[X] = fakeMagData[X];
magData[Y] = fakeMagData[Y];
magData[Z] = fakeMagData[Z];
return true;
}
bool fakeMagDetect(magDev_t *mag)
{
mag->init = fakeMagInit;
mag->read = fakeMagRead;
return true;
}
#endif // USE_FAKE_MAG

View File

@ -0,0 +1,22 @@
/*
* 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/>.
*/
#pragma once
struct magDev_s;
bool fakeMagDetect(struct magDev_s *mag);
void fakeMagSet(int16_t x, int16_t y, int16_t z);

View File

@ -55,7 +55,7 @@ void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
typedef enum {
INPUT_MODE_PPM,
INPUT_MODE_PWM,
INPUT_MODE_PWM
} pwmInputMode_t;
typedef struct {

View File

@ -7,7 +7,7 @@ enum rcc_reg {
RCC_AHB,
RCC_APB2,
RCC_APB1,
RCC_AHB1,
RCC_AHB1
};
#define RCC_ENCODE(reg, mask) (((reg) << 5) | LOG2_32BIT(mask))

View File

@ -106,7 +106,7 @@ enum {
NRF24L01_1D_FEATURE_EN_DPL = 2,
NRF24L01_1D_FEATURE_EN_ACK_PAY = 1,
NRF24L01_1D_FEATURE_EN_DYN_ACK = 0,
NRF24L01_1D_FEATURE_EN_DYN_ACK = 0
};
// Pre-shifted and combined bits
@ -162,7 +162,7 @@ enum {
NRF24L01_06_RF_SETUP_RF_PWR_n6dbm = 0x04,
NRF24L01_06_RF_SETUP_RF_PWR_0dbm = 0x06,
NRF24L01_1C_DYNPD_ALL_PIPES = 0x3F,
NRF24L01_1C_DYNPD_ALL_PIPES = 0x3F
};
// Pipes

View File

@ -20,7 +20,7 @@
typedef enum {
RX_SPI_SOFTSPI,
RX_SPI_HARDSPI,
RX_SPI_HARDSPI
} rx_spi_type_e;
#define RX_SPI_MAX_PAYLOAD_SIZE 32

View File

@ -67,7 +67,7 @@ typedef enum {
SDCARD_STATE_SENDING_WRITE,
SDCARD_STATE_WAITING_FOR_WRITE,
SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE,
SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE
} sdcardState_e;
typedef struct sdcard_t {
@ -352,7 +352,7 @@ static bool sdcard_readOCRRegister(uint32_t *result)
typedef enum {
SDCARD_RECEIVE_SUCCESS,
SDCARD_RECEIVE_BLOCK_IN_PROGRESS,
SDCARD_RECEIVE_ERROR,
SDCARD_RECEIVE_ERROR
} sdcardReceiveBlockStatus_e;
/**

View File

@ -43,7 +43,7 @@ typedef struct sdcardMetadata_s {
typedef enum {
SDCARD_BLOCK_OPERATION_READ,
SDCARD_BLOCK_OPERATION_WRITE,
SDCARD_BLOCK_OPERATION_ERASE,
SDCARD_BLOCK_OPERATION_ERASE
} sdcardBlockOperation_e;
typedef enum {

View File

@ -17,6 +17,18 @@
#pragma once
typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1,
CW90_DEG = 2,
CW180_DEG = 3,
CW270_DEG = 4,
CW0_DEG_FLIP = 5,
CW90_DEG_FLIP = 6,
CW180_DEG_FLIP = 7,
CW270_DEG_FLIP = 8
} sensor_align_e;
struct accDev_s;
typedef void (*sensorInitFuncPtr)(void); // sensor init prototype
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype

View File

@ -24,7 +24,7 @@
typedef enum {
BAUDRATE_NORMAL = 19200,
BAUDRATE_KISS = 38400,
BAUDRATE_CASTLE = 18880,
BAUDRATE_CASTLE = 18880
} escBaudRate_e;
typedef enum {
@ -32,7 +32,7 @@ typedef enum {
PROTOCOL_BLHELI = 1,
PROTOCOL_KISS = 2,
PROTOCOL_KISSALL = 3,
PROTOCOL_CASTLE = 4,
PROTOCOL_CASTLE = 4
} escProtocol_e;
#if defined(USE_ESCSERIAL)

View File

@ -25,4 +25,8 @@ typedef struct vcdProfile_s {
int8_t v_offset;
} vcdProfile_t;
enum VIDEO_SYSTEMS { VIDEO_SYSTEM_AUTO = 0, VIDEO_SYSTEM_PAL, VIDEO_SYSTEM_NTSC };
enum VIDEO_SYSTEMS {
VIDEO_SYSTEM_AUTO = 0,
VIDEO_SYSTEM_PAL,
VIDEO_SYSTEM_NTSC
};

View File

@ -230,13 +230,6 @@ void resetBarometerConfig(barometerConfig_t *barometerConfig)
}
#endif
void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
{
sensorAlignmentConfig->gyro_align = ALIGN_DEFAULT;
sensorAlignmentConfig->acc_align = ALIGN_DEFAULT;
sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
}
#ifdef LED_STRIP
void resetLedStripConfig(ledStripConfig_t *ledStripConfig)
{
@ -587,22 +580,24 @@ void createDefaultConfig(master_t *config)
config->debug_mode = DEBUG_MODE;
resetAccelerometerTrims(&config->sensorTrims.accZero);
resetAccelerometerTrims(&config->accelerometerConfig.accZero);
resetSensorAlignment(&config->sensorAlignmentConfig);
config->gyroConfig.gyro_align = ALIGN_DEFAULT;
config->accelerometerConfig.acc_align = ALIGN_DEFAULT;
config->compassConfig.mag_align = ALIGN_DEFAULT;
config->boardAlignment.rollDegrees = 0;
config->boardAlignment.pitchDegrees = 0;
config->boardAlignment.yawDegrees = 0;
config->sensorSelectionConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
config->accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
config->max_angle_inclination = 700; // 70 degrees
config->rcControlsConfig.yaw_control_direction = 1;
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
// xxx_hardware: 0:default/autodetect, 1: disable
config->sensorSelectionConfig.mag_hardware = 1;
config->compassConfig.mag_hardware = 1;
config->sensorSelectionConfig.baro_hardware = 1;
config->barometerConfig.baro_hardware = 1;
resetBatteryConfig(&config->batteryConfig);
@ -842,7 +837,7 @@ void activateConfig(void)
#endif
useFailsafeConfig(&masterConfig.failsafeConfig);
setAccelerationTrims(&sensorTrims()->accZero);
setAccelerationTrims(&accelerometerConfig()->accZero);
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
mixerUseConfigs(
@ -1004,13 +999,6 @@ void validateAndFixGyroConfig(void)
}
}
void readEEPROMAndNotify(void)
{
// re-read written data
readEEPROM();
beeperConfirmationBeeps(1);
}
void ensureEEPROMContainsValidData(void)
{
if (isEEPROMContentValid()) {
@ -1029,7 +1017,8 @@ void resetEEPROM(void)
void saveConfigAndNotify(void)
{
writeEEPROM();
readEEPROMAndNotify();
readEEPROM();
beeperConfirmationBeeps(1);
}
void changeProfile(uint8_t profileIndex)

View File

@ -55,7 +55,7 @@ typedef enum {
FEATURE_VTX = 1 << 24,
FEATURE_RX_SPI = 1 << 25,
FEATURE_SOFTSPI = 1 << 26,
FEATURE_ESC_TELEMETRY = 1 << 27,
FEATURE_ESC_TELEMETRY = 1 << 27
} features_e;
void beeperOffSet(uint32_t mask);
@ -70,7 +70,6 @@ void setPreferredBeeperOffMask(uint32_t mask);
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
void resetEEPROM(void);
void readEEPROMAndNotify(void);
void ensureEEPROMContainsValidData(void);
void saveConfigAndNotify(void);

View File

@ -176,7 +176,7 @@ typedef enum {
} mspSDCardState_e;
typedef enum {
MSP_SDCARD_FLAG_SUPPORTTED = 1,
MSP_SDCARD_FLAG_SUPPORTTED = 1
} mspSDCardFlags_e;
#define RATEPROFILE_MASK (1 << 7)
@ -606,6 +606,8 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4);
sbufWriteU32(dst, packFlightModeFlags());
sbufWriteU8(dst, masterConfig.current_profile_index);
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
sbufWriteU16(dst, 0); // gyro cycle time
break;
case MSP_RAW_IMU:
@ -1079,9 +1081,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
break;
case MSP_SENSOR_ALIGNMENT:
sbufWriteU8(dst, sensorAlignmentConfig()->gyro_align);
sbufWriteU8(dst, sensorAlignmentConfig()->acc_align);
sbufWriteU8(dst, sensorAlignmentConfig()->mag_align);
sbufWriteU8(dst, gyroConfig()->gyro_align);
sbufWriteU8(dst, accelerometerConfig()->acc_align);
sbufWriteU8(dst, compassConfig()->mag_align);
break;
case MSP_ADVANCED_CONFIG:
@ -1125,9 +1127,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
break;
case MSP_SENSOR_CONFIG:
sbufWriteU8(dst, sensorSelectionConfig()->acc_hardware);
sbufWriteU8(dst, sensorSelectionConfig()->baro_hardware);
sbufWriteU8(dst, sensorSelectionConfig()->mag_hardware);
sbufWriteU8(dst, accelerometerConfig()->acc_hardware);
sbufWriteU8(dst, barometerConfig()->baro_hardware);
sbufWriteU8(dst, compassConfig()->mag_hardware);
break;
case MSP_REBOOT:
@ -1432,9 +1434,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
break;
case MSP_SET_SENSOR_ALIGNMENT:
sensorAlignmentConfig()->gyro_align = sbufReadU8(src);
sensorAlignmentConfig()->acc_align = sbufReadU8(src);
sensorAlignmentConfig()->mag_align = sbufReadU8(src);
gyroConfig()->gyro_align = sbufReadU8(src);
accelerometerConfig()->acc_align = sbufReadU8(src);
compassConfig()->mag_align = sbufReadU8(src);
break;
case MSP_SET_ADVANCED_CONFIG:
@ -1487,9 +1489,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
break;
case MSP_SET_SENSOR_CONFIG:
sensorSelectionConfig()->acc_hardware = sbufReadU8(src);
sensorSelectionConfig()->baro_hardware = sbufReadU8(src);
sensorSelectionConfig()->mag_hardware = sbufReadU8(src);
accelerometerConfig()->acc_hardware = sbufReadU8(src);
barometerConfig()->baro_hardware = sbufReadU8(src);
compassConfig()->mag_hardware = sbufReadU8(src);
break;
case MSP_RESET_CONF:
@ -1559,7 +1561,10 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
osdProfile()->alt_alarm = sbufReadU16(src);
} else {
// set a position setting
osdProfile()->item_pos[addr] = sbufReadU16(src);
const uint16_t pos = sbufReadU16(src);
if (addr < OSD_ITEM_COUNT) {
osdProfile()->item_pos[addr] = pos;
}
}
}
break;

View File

@ -160,7 +160,7 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs)
static void taskUpdateCompass(timeUs_t currentTimeUs)
{
if (sensors(SENSOR_MAG)) {
compassUpdate(currentTimeUs, &sensorTrims()->magZero);
compassUpdate(currentTimeUs, &compassConfig()->magZero);
}
}
#endif

View File

@ -373,18 +373,6 @@ void mwDisarm(void)
}
}
#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_SMARTPORT)
#ifdef TELEMETRY
static void releaseSharedTelemetryPorts(void) {
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
while (sharedPort) {
mspSerialReleasePortIfAllocated(sharedPort);
sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
}
}
#endif
void mwArm(void)
{
static bool firstArmingCalibrationWasCompleted;

View File

@ -207,8 +207,7 @@ typedef enum {
ADJUSTMENT_RC_RATE_YAW,
ADJUSTMENT_D_SETPOINT,
ADJUSTMENT_D_SETPOINT_TRANSITION,
ADJUSTMENT_FUNCTION_COUNT,
ADJUSTMENT_FUNCTION_COUNT
} adjustmentFunction_e;

View File

@ -43,7 +43,7 @@ typedef enum {
PASSTHRU_MODE = (1 << 8),
SONAR_MODE = (1 << 9),
FAILSAFE_MODE = (1 << 10),
GTUNE_MODE = (1 << 11),
GTUNE_MODE = (1 << 11)
} flightModeFlags_e;
extern uint16_t flightModeFlags;
@ -57,7 +57,7 @@ typedef enum {
GPS_FIX = (1 << 1),
CALIBRATE_MAG = (1 << 2),
SMALL_ANGLE = (1 << 3),
FIXED_WING = (1 << 4), // set when in flying_wing or airplane mode. currently used by althold selection code
FIXED_WING = (1 << 4) // set when in flying_wing or airplane mode. currently used by althold selection code
} stateFlags_t;
#define DISABLE_STATE(mask) (stateFlags &= ~(mask))

View File

@ -177,7 +177,7 @@ void servoMixerInit(servoMixer_t *initialCustomServoMixers)
// enable servos for mixes that require them. note, this shifts motor counts.
useServo = mixers[currentMixerMode].useServo;
// if we want camstab/trig, that also enables servos, even if mixer doesn't
if (feature(FEATURE_SERVO_TILT))
if (feature(FEATURE_SERVO_TILT) || feature(FEATURE_CHANNEL_FORWARDING))
useServo = 1;
// give all servos a default command

View File

@ -35,7 +35,6 @@ enum {
INPUT_RC_AUX4,
INPUT_GIMBAL_PITCH,
INPUT_GIMBAL_ROLL,
INPUT_SOURCE_COUNT
} inputSource_e;
@ -59,8 +58,7 @@ typedef enum {
SERVO_SINGLECOPTER_1 = 3,
SERVO_SINGLECOPTER_2 = 4,
SERVO_SINGLECOPTER_3 = 5,
SERVO_SINGLECOPTER_4 = 6,
SERVO_SINGLECOPTER_4 = 6
} servoIndex_e; // FIXME rename to servoChannel_e
#define SERVO_PLANE_INDEX_MIN SERVO_FLAPS

View File

@ -98,7 +98,7 @@
typedef enum {
AFATFS_SAVE_DIRECTORY_NORMAL,
AFATFS_SAVE_DIRECTORY_FOR_CLOSE,
AFATFS_SAVE_DIRECTORY_DELETED,
AFATFS_SAVE_DIRECTORY_DELETED
} afatfsSaveDirectoryEntryMode_e;
typedef enum {
@ -119,7 +119,7 @@ typedef enum {
typedef enum {
CLUSTER_SEARCH_FREE_AT_BEGINNING_OF_FAT_SECTOR,
CLUSTER_SEARCH_FREE,
CLUSTER_SEARCH_OCCUPIED,
CLUSTER_SEARCH_OCCUPIED
} afatfsClusterSearchCondition_e;
enum {
@ -127,14 +127,14 @@ enum {
AFATFS_CREATEFILE_PHASE_FIND_FILE,
AFATFS_CREATEFILE_PHASE_CREATE_NEW_FILE,
AFATFS_CREATEFILE_PHASE_SUCCESS,
AFATFS_CREATEFILE_PHASE_FAILURE,
AFATFS_CREATEFILE_PHASE_FAILURE
};
typedef enum {
AFATFS_FIND_CLUSTER_IN_PROGRESS,
AFATFS_FIND_CLUSTER_FOUND,
AFATFS_FIND_CLUSTER_FATAL,
AFATFS_FIND_CLUSTER_NOT_FOUND,
AFATFS_FIND_CLUSTER_NOT_FOUND
} afatfsFindClusterStatus_e;
struct afatfsFileOperation_t;
@ -234,7 +234,7 @@ typedef enum {
AFATFS_APPEND_SUPERCLUSTER_PHASE_INIT = 0,
AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FREEFILE_DIRECTORY,
AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FAT,
AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FILE_DIRECTORY,
AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FILE_DIRECTORY
} afatfsAppendSuperclusterPhase_e;
typedef struct afatfsAppendSupercluster_t {
@ -251,7 +251,7 @@ typedef enum {
AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT2,
AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FILE_DIRECTORY,
AFATFS_APPEND_FREE_CLUSTER_PHASE_COMPLETE,
AFATFS_APPEND_FREE_CLUSTER_PHASE_FAILURE,
AFATFS_APPEND_FREE_CLUSTER_PHASE_FAILURE
} afatfsAppendFreeClusterPhase_e;
typedef struct afatfsAppendFreeCluster_t {
@ -286,7 +286,7 @@ typedef enum {
AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_CONTIGUOUS,
AFATFS_TRUNCATE_FILE_PREPEND_TO_FREEFILE,
#endif
AFATFS_TRUNCATE_FILE_SUCCESS,
AFATFS_TRUNCATE_FILE_SUCCESS
} afatfsTruncateFilePhase_e;
typedef struct afatfsTruncateFile_t {
@ -299,7 +299,7 @@ typedef struct afatfsTruncateFile_t {
typedef enum {
AFATFS_DELETE_FILE_DELETE_DIRECTORY_ENTRY,
AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS,
AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS
} afatfsDeleteFilePhase_e;
typedef struct afatfsDeleteFile_t {
@ -323,7 +323,7 @@ typedef enum {
AFATFS_FILE_OPERATION_LOCKED,
#endif
AFATFS_FILE_OPERATION_APPEND_FREE_CLUSTER,
AFATFS_FILE_OPERATION_EXTEND_SUBDIRECTORY,
AFATFS_FILE_OPERATION_EXTEND_SUBDIRECTORY
} afatfsFileOperation_e;
typedef struct afatfsFileOperation_t {

View File

@ -28,13 +28,13 @@ typedef enum {
AFATFS_FILESYSTEM_STATE_UNKNOWN,
AFATFS_FILESYSTEM_STATE_FATAL,
AFATFS_FILESYSTEM_STATE_INITIALIZATION,
AFATFS_FILESYSTEM_STATE_READY,
AFATFS_FILESYSTEM_STATE_READY
} afatfsFilesystemState_e;
typedef enum {
AFATFS_OPERATION_IN_PROGRESS,
AFATFS_OPERATION_SUCCESS,
AFATFS_OPERATION_FAILURE,
AFATFS_OPERATION_FAILURE
} afatfsOperationStatus_e;
typedef enum {
@ -54,7 +54,7 @@ typedef afatfsDirEntryPointer_t afatfsFinder_t;
typedef enum {
AFATFS_SEEK_SET,
AFATFS_SEEK_CUR,
AFATFS_SEEK_END,
AFATFS_SEEK_END
} afatfsSeek_e;
typedef void (*afatfsFileCallback_t)(afatfsFilePtr_t file);

View File

@ -54,7 +54,7 @@ typedef enum {
FAT_FILESYSTEM_TYPE_INVALID,
FAT_FILESYSTEM_TYPE_FAT12,
FAT_FILESYSTEM_TYPE_FAT16,
FAT_FILESYSTEM_TYPE_FAT32,
FAT_FILESYSTEM_TYPE_FAT32
} fatFilesystemType_e;
typedef struct mbrPartitionEntry_t {

View File

@ -43,7 +43,7 @@ typedef enum {
BEEPER_USB, // Some boards have beeper powered USB connected
BEEPER_ALL, // Turn ON or OFF all beeper conditions
BEEPER_PREFERENCE, // Save preferred beeper configuration
BEEPER_PREFERENCE // Save preferred beeper configuration
// BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum
} beeperMode_e;

View File

@ -503,7 +503,7 @@ int flashfsIdentifyStartOfFreeSpace()
/* We don't expect valid data to ever contain this many consecutive uint32_t's of all 1 bits: */
FREE_BLOCK_TEST_SIZE_INTS = 4, // i.e. 16 bytes
FREE_BLOCK_TEST_SIZE_BYTES = FREE_BLOCK_TEST_SIZE_INTS * sizeof(uint32_t),
FREE_BLOCK_TEST_SIZE_BYTES = FREE_BLOCK_TEST_SIZE_INTS * sizeof(uint32_t)
};
union {

View File

@ -175,7 +175,7 @@ typedef enum {
GPS_CHANGE_BAUD,
GPS_CONFIGURE,
GPS_RECEIVING_DATA,
GPS_LOST_COMMUNICATION,
GPS_LOST_COMMUNICATION
} gpsState_e;
gpsData_t gpsData;

View File

@ -51,7 +51,7 @@ typedef enum {
typedef enum {
GPS_AUTOCONFIG_OFF = 0,
GPS_AUTOCONFIG_ON,
GPS_AUTOCONFIG_ON
} gpsAutoConfig_e;
typedef enum {
@ -78,11 +78,9 @@ typedef enum {
GPS_MESSAGE_STATE_IDLE = 0,
GPS_MESSAGE_STATE_INIT,
GPS_MESSAGE_STATE_SBAS,
GPS_MESSAGE_STATE_MAX = GPS_MESSAGE_STATE_SBAS
GPS_MESSAGE_STATE_ENTRY_COUNT
} gpsMessageState_e;
#define GPS_MESSAGE_STATE_ENTRY_COUNT (GPS_MESSAGE_STATE_MAX + 1)
typedef struct gpsData_s {
uint8_t state; // GPS thread state. Used for detecting cable disconnects and configuring attached devices
uint8_t baudrateIndex; // index into auto-detecting or current baudrate

View File

@ -114,7 +114,7 @@ typedef enum {
COLOR_BLUE,
COLOR_DARK_VIOLET,
COLOR_MAGENTA,
COLOR_DEEP_PINK,
COLOR_DEEP_PINK
} colorId_e;
const hsvColor_t hsv[] = {

View File

@ -108,7 +108,7 @@ typedef enum {
LED_FUNCTION_BATTERY,
LED_FUNCTION_RSSI,
LED_FUNCTION_GPS,
LED_FUNCTION_THRUST_RING,
LED_FUNCTION_THRUST_RING
} ledBaseFunctionId_e;
typedef enum {
@ -117,7 +117,7 @@ typedef enum {
LED_OVERLAY_BLINK,
LED_OVERLAY_LANDING_FLASH,
LED_OVERLAY_INDICATOR,
LED_OVERLAY_WARNING,
LED_OVERLAY_WARNING
} ledOverlayId_e;
typedef struct modeColorIndexes_s {

View File

@ -333,6 +333,27 @@ static void osdDrawSingleElement(uint8_t item)
return;
}
case OSD_ROLL_PIDS:
{
const pidProfile_t *pidProfile = &currentProfile->pidProfile;
sprintf(buff, "ROL %3d %3d %3d", pidProfile->P8[PIDROLL], pidProfile->I8[PIDROLL], pidProfile->D8[PIDROLL]);
break;
}
case OSD_PITCH_PIDS:
{
const pidProfile_t *pidProfile = &currentProfile->pidProfile;
sprintf(buff, "PIT %3d %3d %3d", pidProfile->P8[PIDPITCH], pidProfile->I8[PIDPITCH], pidProfile->D8[PIDPITCH]);
break;
}
case OSD_YAW_PIDS:
{
const pidProfile_t *pidProfile = &currentProfile->pidProfile;
sprintf(buff, "YAW %3d %3d %3d", pidProfile->P8[PIDYAW], pidProfile->I8[PIDYAW], pidProfile->D8[PIDYAW]);
break;
}
default:
return;
}
@ -372,6 +393,9 @@ void osdDrawElements(void)
osdDrawSingleElement(OSD_MAH_DRAWN);
osdDrawSingleElement(OSD_CRAFT_NAME);
osdDrawSingleElement(OSD_ALTITUDE);
osdDrawSingleElement(OSD_ROLL_PIDS);
osdDrawSingleElement(OSD_PITCH_PIDS);
osdDrawSingleElement(OSD_YAW_PIDS);
#ifdef GPS
#ifdef CMS
@ -403,6 +427,9 @@ void osdResetConfig(osd_profile_t *osdProfile)
osdProfile->item_pos[OSD_GPS_SPEED] = OSD_POS(2, 2);
osdProfile->item_pos[OSD_GPS_SATS] = OSD_POS(2, 12);
osdProfile->item_pos[OSD_ALTITUDE] = OSD_POS(1, 5);
osdProfile->item_pos[OSD_ROLL_PIDS] = OSD_POS(2, 10) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_PITCH_PIDS] = OSD_POS(2, 11) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_YAW_PIDS] = OSD_POS(2, 12) | VISIBLE_FLAG;
osdProfile->rssi_alarm = 20;
osdProfile->cap_alarm = 2200;

View File

@ -40,6 +40,9 @@ typedef enum {
OSD_GPS_SPEED,
OSD_GPS_SATS,
OSD_ALTITUDE,
OSD_ROLL_PIDS,
OSD_PITCH_PIDS,
OSD_YAW_PIDS,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;

View File

@ -75,8 +75,7 @@ typedef enum {
SERIAL_PORT_USART8,
SERIAL_PORT_USB_VCP = 20,
SERIAL_PORT_SOFTSERIAL1 = 30,
SERIAL_PORT_SOFTSERIAL2,
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
SERIAL_PORT_SOFTSERIAL2
} serialPortIdentifier_e;
extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];

158
src/main/io/serial.h.orig Normal file
View File

@ -0,0 +1,158 @@
/*
* 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/>.
*/
#pragma once
#include "drivers/serial.h"
typedef enum {
PORTSHARING_UNUSED = 0,
PORTSHARING_NOT_SHARED,
PORTSHARING_SHARED
} portSharing_e;
typedef enum {
FUNCTION_NONE = 0,
FUNCTION_MSP = (1 << 0), // 1
FUNCTION_GPS = (1 << 1), // 2
FUNCTION_TELEMETRY_FRSKY = (1 << 2), // 4
FUNCTION_TELEMETRY_HOTT = (1 << 3), // 8
FUNCTION_TELEMETRY_LTM = (1 << 4), // 16
FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), // 32
FUNCTION_RX_SERIAL = (1 << 6), // 64
FUNCTION_BLACKBOX = (1 << 7), // 128
FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512
<<<<<<< HEAD
FUNCTION_TELEMETRY_ESC = (1 << 10), // 1024
FUNCTION_VTX_CONTROL = (1 << 11),// 2048
=======
FUNCTION_TELEMETRY_ESC = (1 << 10) // 1024
>>>>>>> betaflight/master
} serialPortFunction_e;
typedef enum {
BAUD_AUTO = 0,
BAUD_9600,
BAUD_19200,
BAUD_38400,
BAUD_57600,
BAUD_115200,
BAUD_230400,
BAUD_250000,
BAUD_400000,
BAUD_460800,
BAUD_500000,
BAUD_921600,
BAUD_1000000,
BAUD_1500000,
BAUD_2000000,
BAUD_2470000
} baudRate_e;
extern const uint32_t baudRates[];
// serial port identifiers are now fixed, these values are used by MSP commands.
typedef enum {
SERIAL_PORT_NONE = -1,
SERIAL_PORT_USART1 = 0,
SERIAL_PORT_USART2,
SERIAL_PORT_USART3,
SERIAL_PORT_USART4,
SERIAL_PORT_USART5,
SERIAL_PORT_USART6,
SERIAL_PORT_USART7,
SERIAL_PORT_USART8,
SERIAL_PORT_USB_VCP = 20,
SERIAL_PORT_SOFTSERIAL1 = 30,
SERIAL_PORT_SOFTSERIAL2
} serialPortIdentifier_e;
extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
//
// runtime
//
typedef struct serialPortUsage_s {
serialPortIdentifier_e identifier;
serialPort_t *serialPort;
serialPortFunction_e function;
} serialPortUsage_t;
serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);
serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);
//
// configuration
//
typedef struct serialPortConfig_s {
serialPortIdentifier_e identifier;
uint16_t functionMask;
uint8_t msp_baudrateIndex;
uint8_t gps_baudrateIndex;
uint8_t blackbox_baudrateIndex;
uint8_t telemetry_baudrateIndex; // not used for all telemetry systems, e.g. HoTT only works at 19200.
} serialPortConfig_t;
typedef struct serialConfig_s {
uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else.
serialPortConfig_t portConfigs[SERIAL_PORT_COUNT];
} serialConfig_t;
typedef void serialConsumer(uint8_t);
//
// configuration
//
void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
void serialRemovePort(serialPortIdentifier_e identifier);
uint8_t serialGetAvailablePortCount(void);
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
bool isSerialConfigValid(serialConfig_t *serialConfig);
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
portSharing_e determinePortSharing(serialPortConfig_t *portConfig, serialPortFunction_e function);
bool isSerialPortShared(serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction);
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier);
int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier);
//
// runtime
//
serialPort_t *openSerialPort(
serialPortIdentifier_e identifier,
serialPortFunction_e function,
serialReceiveCallbackPtr rxCallback,
uint32_t baudrate,
portMode_t mode,
portOptions_t options
);
void closeSerialPort(serialPort_t *serialPort);
void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
baudRate_e lookupBaudRateIndex(uint32_t baudRate);
//
// msp/cli/bootloader
//
void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar);
void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC);

View File

@ -210,7 +210,7 @@ typedef enum {
DUMP_ALL = (1 << 3),
DO_DIFF = (1 << 4),
SHOW_DEFAULTS = (1 << 5),
HIDE_UNUSED = (1 << 6),
HIDE_UNUSED = (1 << 6)
} dumpFlags_e;
static const char* const emptyName = "-";
@ -803,9 +803,9 @@ const clivalue_t valueTable[] = {
{ "use_vbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->useVBatAlerts, .config.lookup = { TABLE_OFF_ON } },
{ "use_consumption_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->useConsumptionAlerts, .config.lookup = { TABLE_OFF_ON } },
{ "consumption_warning_percentage", VAR_UINT8 | MASTER_VALUE, &batteryConfig()->consumptionWarningPercentage, .config.minmax = { 0, 100 } },
{ "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorAlignmentConfig()->gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
{ "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorAlignmentConfig()->acc_align, .config.lookup = { TABLE_ALIGNMENT } },
{ "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorAlignmentConfig()->mag_align, .config.lookup = { TABLE_ALIGNMENT } },
{ "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gyroConfig()->gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
{ "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &accelerometerConfig()->acc_align, .config.lookup = { TABLE_ALIGNMENT } },
{ "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &compassConfig()->mag_align, .config.lookup = { TABLE_ALIGNMENT } },
{ "align_board_roll", VAR_INT16 | MASTER_VALUE, &boardAlignment()->rollDegrees, .config.minmax = { -180, 360 } },
{ "align_board_pitch", VAR_INT16 | MASTER_VALUE, &boardAlignment()->pitchDegrees, .config.minmax = { -180, 360 } },
@ -869,7 +869,7 @@ const clivalue_t valueTable[] = {
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &rxConfig()->rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &rxConfig()->rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorSelectionConfig()->acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &accelerometerConfig()->acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
{ "acc_lpf_hz", VAR_UINT16 | MASTER_VALUE, &accelerometerConfig()->acc_lpf_hz, .config.minmax = { 0, 400 } },
{ "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &imuConfig()->accDeadband.xy, .config.minmax = { 0, 100 } },
{ "accz_deadband", VAR_UINT8 | MASTER_VALUE, &imuConfig()->accDeadband.z, .config.minmax = { 0, 100 } },
@ -882,11 +882,11 @@ const clivalue_t valueTable[] = {
{ "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &barometerConfig()->baro_noise_lpf, .config.minmax = { 0 , 1 } },
{ "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &barometerConfig()->baro_cf_vel, .config.minmax = { 0 , 1 } },
{ "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &barometerConfig()->baro_cf_alt, .config.minmax = { 0 , 1 } },
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorSelectionConfig()->baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &barometerConfig()->baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
#endif
#ifdef MAG
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorSelectionConfig()->mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &compassConfig()->mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &compassConfig()->mag_declination, .config.minmax = { -18000, 18000 } },
#endif
{ "dterm_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dterm_filter_type, .config.lookup = { TABLE_LOWPASS_TYPE } },
@ -945,9 +945,9 @@ const clivalue_t valueTable[] = {
#endif
#ifdef MAG
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &sensorTrims()->magZero.raw[X], .config.minmax = { -32768, 32767 } },
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &sensorTrims()->magZero.raw[Y], .config.minmax = { -32768, 32767 } },
{ "magzero_z", VAR_INT16 | MASTER_VALUE, &sensorTrims()->magZero.raw[Z], .config.minmax = { -32768, 32767 } },
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &compassConfig()->magZero.raw[X], .config.minmax = { -32768, 32767 } },
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &compassConfig()->magZero.raw[Y], .config.minmax = { -32768, 32767 } },
{ "magzero_z", VAR_INT16 | MASTER_VALUE, &compassConfig()->magZero.raw[Z], .config.minmax = { -32768, 32767 } },
#endif
#ifdef LED_STRIP
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &ledStripConfig()->ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
@ -967,21 +967,24 @@ const clivalue_t valueTable[] = {
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->time_alarm, .config.minmax = { 0, 60 } },
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->alt_alarm, .config.minmax = { 0, 10000 } },
{ "osd_main_voltage_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { 0, 65536 } },
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_RSSI_VALUE], .config.minmax = { 0, 65536 } },
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYTIME], .config.minmax = { 0, 65536 } },
{ "osd_ontime_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ONTIME], .config.minmax = { 0, 65536 } },
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYMODE], .config.minmax = { 0, 65536 } },
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, 65536 } },
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, 65536 } },
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, 65536 } },
{ "osd_artificial_horizon", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, 65536 } },
{ "osd_current_draw_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, 65536 } },
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, 65536 } },
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, 65536 } },
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SPEED], .config.minmax = { 0, 65536 } },
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SATS], .config.minmax = { 0, 65536 } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } },
{ "osd_main_voltage_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { 0, UINT16_MAX } },
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_RSSI_VALUE], .config.minmax = { 0, UINT16_MAX } },
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYTIME], .config.minmax = { 0, UINT16_MAX } },
{ "osd_ontime_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ONTIME], .config.minmax = { 0, UINT16_MAX } },
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYMODE], .config.minmax = { 0, UINT16_MAX } },
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, UINT16_MAX } },
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, UINT16_MAX } },
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, UINT16_MAX } },
{ "osd_artificial_horizon", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, UINT16_MAX } },
{ "osd_current_draw_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, UINT16_MAX } },
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, UINT16_MAX } },
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, UINT16_MAX } },
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SPEED], .config.minmax = { 0, UINT16_MAX } },
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SATS], .config.minmax = { 0, UINT16_MAX } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ALTITUDE], .config.minmax = { 0, UINT16_MAX } },
{ "osd_pid_roll_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ROLL_PIDS], .config.minmax = { 0, UINT16_MAX } },
{ "osd_pid_pitch_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_PITCH_PIDS], .config.minmax = { 0, UINT16_MAX } },
{ "osd_pid_yaw_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_YAW_PIDS], .config.minmax = { 0, UINT16_MAX } },
#endif
#ifdef USE_MAX7456
{ "vcd_video_system", VAR_UINT8 | MASTER_VALUE, &vcdProfile()->video_system, .config.minmax = { 0, 2 } },

View File

@ -424,11 +424,7 @@ void init(void)
#else
const void *sonarConfig = NULL;
#endif
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,
&masterConfig.sensorSelectionConfig,
compassConfig()->mag_declination,
&masterConfig.gyroConfig,
sonarConfig)) {
if (!sensorsAutodetect(gyroConfig(), accelerometerConfig(), compassConfig(), barometerConfig(), sonarConfig)) {
// if gyro was not detected due to whatever reason, we give up now.
failureMode(FAILURE_MISSING_ACC);
}

View File

@ -61,7 +61,7 @@
enum {
RATE_LOW = 0,
RATE_MID = 1,
RATE_HIGH= 2,
RATE_HIGH= 2
};
#define FLAG_FLIP 0x10 // goes to rudder channel

View File

@ -89,7 +89,7 @@
enum {
RATE_LOW = 0,
RATE_MID = 1,
RATE_HIGH = 2,
RATE_HIGH = 2
};
enum {
@ -97,7 +97,7 @@ enum {
FLAG_PICTURE = 0x02,
FLAG_VIDEO = 0x04,
FLAG_RTH = 0x08,
FLAG_HEADLESS = 0x10,
FLAG_HEADLESS = 0x10
};
typedef enum {

View File

@ -73,7 +73,7 @@
enum {
RATE_LOW = 0,
RATE_MID = 1,
RATE_HIGH= 2,
RATE_HIGH= 2
};
#define FLAG_PICTURE 0x40

View File

@ -55,9 +55,7 @@ typedef enum {
SERIALRX_XBUS_MODE_B_RJ01 = 6,
SERIALRX_IBUS = 7,
SERIALRX_JETIEXBUS = 8,
SERIALRX_CRSF = 9,
SERIALRX_PROVIDER_COUNT,
SERIALRX_PROVIDER_MAX = SERIALRX_PROVIDER_COUNT - 1
SERIALRX_CRSF = 9
} SerialRXType;
#define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 12
@ -89,14 +87,14 @@ typedef enum {
RX_FAILSAFE_MODE_AUTO = 0,
RX_FAILSAFE_MODE_HOLD,
RX_FAILSAFE_MODE_SET,
RX_FAILSAFE_MODE_INVALID,
RX_FAILSAFE_MODE_INVALID
} rxFailsafeChannelMode_e;
#define RX_FAILSAFE_MODE_COUNT 3
typedef enum {
RX_FAILSAFE_TYPE_FLIGHT = 0,
RX_FAILSAFE_TYPE_AUX,
RX_FAILSAFE_TYPE_AUX
} rxFailsafeChannelType_e;
#define RX_FAILSAFE_TYPE_COUNT 2

View File

@ -215,7 +215,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
}
}
alignSensors(acc.accSmooth, acc.accAlign);
alignSensors(acc.accSmooth, acc.dev.accAlign);
if (!isAccelerationCalibrationComplete()) {
performAcclerationCalibration(rollAndPitchTrims);

View File

@ -32,13 +32,11 @@ typedef enum {
ACC_MPU6000 = 7,
ACC_MPU6500 = 8,
ACC_ICM20689 = 9,
ACC_FAKE = 10,
ACC_MAX = ACC_FAKE
ACC_FAKE = 10
} accelerationSensor_e;
typedef struct acc_s {
accDev_t dev;
sensor_align_e accAlign;
uint32_t accSamplingInterval;
int32_t accSmooth[XYZ_AXIS_COUNT];
} acc_t;
@ -58,6 +56,9 @@ typedef union rollAndPitchTrims_u {
typedef struct accelerometerConfig_s {
uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
sensor_align_e acc_align; // acc alignment
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
flightDynamicsTrims_t accZero;
} accelerometerConfig_t;
void accInit(uint32_t gyroTargetLooptime);

View File

@ -24,13 +24,13 @@ typedef enum {
BARO_NONE = 1,
BARO_BMP085 = 2,
BARO_MS5611 = 3,
BARO_BMP280 = 4,
BARO_MAX = BARO_BMP280
BARO_BMP280 = 4
} baroSensor_e;
#define BARO_SAMPLE_COUNT_MAX 48
typedef struct barometerConfig_s {
uint8_t baro_hardware; // Barometer hardware to use
uint8_t baro_sample_count; // size of baro filter array
float baro_noise_lpf; // additional LPF to reduce baro noise
float baro_cf_vel; // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity)

View File

@ -31,15 +31,13 @@ typedef enum {
CURRENT_SENSOR_NONE = 0,
CURRENT_SENSOR_ADC,
CURRENT_SENSOR_VIRTUAL,
CURRENT_SENSOR_ESC,
CURRENT_SENSOR_MAX = CURRENT_SENSOR_ESC
CURRENT_SENSOR_ESC
} currentSensor_e;
typedef enum {
BATTERY_SENSOR_NONE = 0,
BATTERY_SENSOR_ADC,
BATTERY_SENSOR_ESC,
BATTERY_SENSOR_MAX = BATTERY_SENSOR_ESC
BATTERY_SENSOR_ESC
} batterySensor_e;
typedef struct batteryConfig_s {

View File

@ -23,7 +23,7 @@
#include "common/maths.h"
#include "common/axis.h"
#include "sensors.h"
#include "drivers/sensor.h"
#include "boardalignment.h"

View File

@ -60,7 +60,7 @@ void compassUpdate(uint32_t currentTime, flightDynamicsTrims_t *magZero)
mag.dev.read(magADCRaw);
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) mag.magADC[axis] = magADCRaw[axis]; // int32_t copy to work with
alignSensors(mag.magADC, mag.magAlign);
alignSensors(mag.magADC, mag.dev.magAlign);
if (STATE(CALIBRATE_MAG)) {
tCal = currentTime;

View File

@ -28,13 +28,11 @@ typedef enum {
MAG_NONE = 1,
MAG_HMC5883 = 2,
MAG_AK8975 = 3,
MAG_AK8963 = 4,
MAG_MAX = MAG_AK8963
MAG_AK8963 = 4
} magSensor_e;
typedef struct mag_s {
magDev_t dev;
sensor_align_e magAlign;
int32_t magADC[XYZ_AXIS_COUNT];
float magneticDeclination;
} mag_t;
@ -44,6 +42,9 @@ extern mag_t mag;
typedef struct compassConfig_s {
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
sensor_align_e mag_align; // mag alignment
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
flightDynamicsTrims_t magZero;
} compassConfig_t;
void compassInit(void);

View File

@ -181,7 +181,7 @@ void gyroUpdate(void)
gyroADC[Y] = gyro.dev.gyroADCRaw[Y];
gyroADC[Z] = gyro.dev.gyroADCRaw[Z];
alignSensors(gyroADC, gyro.gyroAlign);
alignSensors(gyroADC, gyro.dev.gyroAlign);
const bool calibrationComplete = isGyroCalibrationComplete();
if (!calibrationComplete) {

View File

@ -31,20 +31,19 @@ typedef enum {
GYRO_MPU6500,
GYRO_MPU9250,
GYRO_ICM20689,
GYRO_FAKE,
GYRO_MAX = GYRO_FAKE
GYRO_FAKE
} gyroSensor_e;
typedef struct gyro_s {
gyroDev_t dev;
uint32_t targetLooptime;
sensor_align_e gyroAlign;
float gyroADCf[XYZ_AXIS_COUNT];
} gyro_t;
extern gyro_t gyro;
typedef struct gyroConfig_s {
sensor_align_e gyro_align; // gyro alignment
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
uint8_t gyro_sync_denom; // Gyro sample divider
uint8_t gyro_soft_lpf_type;

View File

@ -35,6 +35,7 @@
#include "drivers/accgyro.h"
#include "drivers/accgyro_adxl345.h"
#include "drivers/accgyro_bma280.h"
#include "drivers/accgyro_fake.h"
#include "drivers/accgyro_l3g4200d.h"
#include "drivers/accgyro_mma845x.h"
#include "drivers/accgyro_mpu.h"
@ -54,12 +55,14 @@
#include "drivers/barometer.h"
#include "drivers/barometer_bmp085.h"
#include "drivers/barometer_bmp280.h"
#include "drivers/barometer_fake.h"
#include "drivers/barometer_ms5611.h"
#include "drivers/compass.h"
#include "drivers/compass_hmc5883l.h"
#include "drivers/compass_ak8975.h"
#include "drivers/compass_ak8963.h"
#include "drivers/compass_fake.h"
#include "drivers/compass_hmc5883l.h"
#include "drivers/sonar_hcsr04.h"
@ -94,84 +97,21 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
#endif
}
#ifdef USE_FAKE_GYRO
int16_t fake_gyro_values[XYZ_AXIS_COUNT] = { 0,0,0 };
static void fakeGyroInit(gyroDev_t *gyro)
{
UNUSED(gyro);
}
static bool fakeGyroRead(gyroDev_t *gyro)
{
for (int i = 0; i < XYZ_AXIS_COUNT; ++i) {
gyro->gyroADCRaw[X] = fake_gyro_values[i];
}
return true;
}
static bool fakeGyroReadTemp(int16_t *tempData)
{
UNUSED(tempData);
return true;
}
static bool fakeGyroInitStatus(gyroDev_t *gyro)
{
UNUSED(gyro);
return true;
}
bool fakeGyroDetect(gyroDev_t *gyro)
{
gyro->init = fakeGyroInit;
gyro->intStatus = fakeGyroInitStatus;
gyro->read = fakeGyroRead;
gyro->temperature = fakeGyroReadTemp;
gyro->scale = 1.0f / 16.4f;
return true;
}
#endif
#ifdef USE_FAKE_ACC
int16_t fake_acc_values[XYZ_AXIS_COUNT] = {0,0,0};
static void fakeAccInit(accDev_t *acc) {UNUSED(acc);}
static bool fakeAccRead(int16_t *accData) {
for(int i=0;i<XYZ_AXIS_COUNT;++i) {
accData[i] = fake_acc_values[i];
}
return true;
}
bool fakeAccDetect(accDev_t *acc)
{
acc->init = fakeAccInit;
acc->read = fakeAccRead;
acc->acc_1G = 512*8;
acc->revisionCode = 0;
return true;
}
#endif
bool detectGyro(void)
bool gyroDetect(gyroDev_t *dev)
{
gyroSensor_e gyroHardware = GYRO_DEFAULT;
gyro.gyroAlign = ALIGN_DEFAULT;
gyro.dev.gyroAlign = ALIGN_DEFAULT;
switch(gyroHardware) {
case GYRO_DEFAULT:
; // fallthrough
case GYRO_MPU6050:
#ifdef USE_GYRO_MPU6050
if (mpu6050GyroDetect(&gyro.dev)) {
if (mpu6050GyroDetect(dev)) {
gyroHardware = GYRO_MPU6050;
#ifdef GYRO_MPU6050_ALIGN
gyro.gyroAlign = GYRO_MPU6050_ALIGN;
gyro.dev.gyroAlign = GYRO_MPU6050_ALIGN;
#endif
break;
}
@ -179,10 +119,10 @@ bool detectGyro(void)
; // fallthrough
case GYRO_L3G4200D:
#ifdef USE_GYRO_L3G4200D
if (l3g4200dDetect(&gyro.dev)) {
if (l3g4200dDetect(dev)) {
gyroHardware = GYRO_L3G4200D;
#ifdef GYRO_L3G4200D_ALIGN
gyro.gyroAlign = GYRO_L3G4200D_ALIGN;
gyro.dev.gyroAlign = GYRO_L3G4200D_ALIGN;
#endif
break;
}
@ -191,10 +131,10 @@ bool detectGyro(void)
case GYRO_MPU3050:
#ifdef USE_GYRO_MPU3050
if (mpu3050Detect(&gyro.dev)) {
if (mpu3050Detect(dev)) {
gyroHardware = GYRO_MPU3050;
#ifdef GYRO_MPU3050_ALIGN
gyro.gyroAlign = GYRO_MPU3050_ALIGN;
gyro.dev.gyroAlign = GYRO_MPU3050_ALIGN;
#endif
break;
}
@ -203,10 +143,10 @@ bool detectGyro(void)
case GYRO_L3GD20:
#ifdef USE_GYRO_L3GD20
if (l3gd20Detect(&gyro.dev)) {
if (l3gd20Detect(dev)) {
gyroHardware = GYRO_L3GD20;
#ifdef GYRO_L3GD20_ALIGN
gyro.gyroAlign = GYRO_L3GD20_ALIGN;
gyro.dev.gyroAlign = GYRO_L3GD20_ALIGN;
#endif
break;
}
@ -215,10 +155,10 @@ bool detectGyro(void)
case GYRO_MPU6000:
#ifdef USE_GYRO_SPI_MPU6000
if (mpu6000SpiGyroDetect(&gyro.dev)) {
if (mpu6000SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU6000;
#ifdef GYRO_MPU6000_ALIGN
gyro.gyroAlign = GYRO_MPU6000_ALIGN;
gyro.dev.gyroAlign = GYRO_MPU6000_ALIGN;
#endif
break;
}
@ -228,14 +168,14 @@ bool detectGyro(void)
case GYRO_MPU6500:
#if defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500)
#ifdef USE_GYRO_SPI_MPU6500
if (mpu6500GyroDetect(&gyro.dev) || mpu6500SpiGyroDetect(&gyro.dev))
if (mpu6500GyroDetect(dev) || mpu6500SpiGyroDetect(dev))
#else
if (mpu6500GyroDetect(&gyro.dev))
if (mpu6500GyroDetect(dev))
#endif
{
gyroHardware = GYRO_MPU6500;
#ifdef GYRO_MPU6500_ALIGN
gyro.gyroAlign = GYRO_MPU6500_ALIGN;
gyro.dev.gyroAlign = GYRO_MPU6500_ALIGN;
#endif
break;
@ -246,11 +186,11 @@ bool detectGyro(void)
case GYRO_MPU9250:
#ifdef USE_GYRO_SPI_MPU9250
if (mpu9250SpiGyroDetect(&gyro.dev))
if (mpu9250SpiGyroDetect(dev))
{
gyroHardware = GYRO_MPU9250;
#ifdef GYRO_MPU9250_ALIGN
gyro.gyroAlign = GYRO_MPU9250_ALIGN;
gyro.dev.gyroAlign = GYRO_MPU9250_ALIGN;
#endif
break;
@ -260,11 +200,11 @@ bool detectGyro(void)
case GYRO_ICM20689:
#ifdef USE_GYRO_SPI_ICM20689
if (icm20689SpiGyroDetect(&gyro.dev))
if (icm20689SpiGyroDetect(dev))
{
gyroHardware = GYRO_ICM20689;
#ifdef GYRO_ICM20689_ALIGN
gyro.gyroAlign = GYRO_ICM20689_ALIGN;
gyro.dev.gyroAlign = GYRO_ICM20689_ALIGN;
#endif
break;
@ -274,7 +214,7 @@ bool detectGyro(void)
case GYRO_FAKE:
#ifdef USE_FAKE_GYRO
if (fakeGyroDetect(&gyro.dev)) {
if (fakeGyroDetect(dev)) {
gyroHardware = GYRO_FAKE;
break;
}
@ -294,7 +234,7 @@ bool detectGyro(void)
return true;
}
static bool detectAcc(accelerationSensor_e accHardwareToUse)
static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
{
accelerationSensor_e accHardware;
@ -303,7 +243,7 @@ static bool detectAcc(accelerationSensor_e accHardwareToUse)
#endif
retry:
acc.accAlign = ALIGN_DEFAULT;
acc.dev.accAlign = ALIGN_DEFAULT;
switch (accHardwareToUse) {
case ACC_DEFAULT:
@ -313,12 +253,12 @@ retry:
acc_params.useFifo = false;
acc_params.dataRate = 800; // unused currently
#ifdef NAZE
if (hardwareRevision < NAZE32_REV5 && adxl345Detect(&acc_params, &acc.dev)) {
if (hardwareRevision < NAZE32_REV5 && adxl345Detect(&acc_params, dev)) {
#else
if (adxl345Detect(&acc_params, &acc.dev)) {
if (adxl345Detect(&acc_params, dev)) {
#endif
#ifdef ACC_ADXL345_ALIGN
acc.accAlign = ACC_ADXL345_ALIGN;
acc.dev.accAlign = ACC_ADXL345_ALIGN;
#endif
accHardware = ACC_ADXL345;
break;
@ -327,9 +267,9 @@ retry:
; // fallthrough
case ACC_LSM303DLHC:
#ifdef USE_ACC_LSM303DLHC
if (lsm303dlhcAccDetect(&acc.dev)) {
if (lsm303dlhcAccDetect(dev)) {
#ifdef ACC_LSM303DLHC_ALIGN
acc.accAlign = ACC_LSM303DLHC_ALIGN;
acc.dev.accAlign = ACC_LSM303DLHC_ALIGN;
#endif
accHardware = ACC_LSM303DLHC;
break;
@ -338,9 +278,9 @@ retry:
; // fallthrough
case ACC_MPU6050: // MPU6050
#ifdef USE_ACC_MPU6050
if (mpu6050AccDetect(&acc.dev)) {
if (mpu6050AccDetect(dev)) {
#ifdef ACC_MPU6050_ALIGN
acc.accAlign = ACC_MPU6050_ALIGN;
acc.dev.accAlign = ACC_MPU6050_ALIGN;
#endif
accHardware = ACC_MPU6050;
break;
@ -351,12 +291,12 @@ retry:
#ifdef USE_ACC_MMA8452
#ifdef NAZE
// Not supported with this frequency
if (hardwareRevision < NAZE32_REV5 && mma8452Detect(&acc.dev)) {
if (hardwareRevision < NAZE32_REV5 && mma8452Detect(dev)) {
#else
if (mma8452Detect(&acc.dev)) {
if (mma8452Detect(dev)) {
#endif
#ifdef ACC_MMA8452_ALIGN
acc.accAlign = ACC_MMA8452_ALIGN;
acc.dev.accAlign = ACC_MMA8452_ALIGN;
#endif
accHardware = ACC_MMA8452;
break;
@ -365,9 +305,9 @@ retry:
; // fallthrough
case ACC_BMA280: // BMA280
#ifdef USE_ACC_BMA280
if (bma280Detect(&acc.dev)) {
if (bma280Detect(dev)) {
#ifdef ACC_BMA280_ALIGN
acc.accAlign = ACC_BMA280_ALIGN;
acc.dev.accAlign = ACC_BMA280_ALIGN;
#endif
accHardware = ACC_BMA280;
break;
@ -376,9 +316,9 @@ retry:
; // fallthrough
case ACC_MPU6000:
#ifdef USE_ACC_SPI_MPU6000
if (mpu6000SpiAccDetect(&acc.dev)) {
if (mpu6000SpiAccDetect(dev)) {
#ifdef ACC_MPU6000_ALIGN
acc.accAlign = ACC_MPU6000_ALIGN;
acc.dev.accAlign = ACC_MPU6000_ALIGN;
#endif
accHardware = ACC_MPU6000;
break;
@ -388,13 +328,13 @@ retry:
case ACC_MPU6500:
#if defined(USE_ACC_MPU6500) || defined(USE_ACC_SPI_MPU6500)
#ifdef USE_ACC_SPI_MPU6500
if (mpu6500AccDetect(&acc.dev) || mpu6500SpiAccDetect(&acc.dev))
if (mpu6500AccDetect(dev) || mpu6500SpiAccDetect(dev))
#else
if (mpu6500AccDetect(&acc.dev))
if (mpu6500AccDetect(dev))
#endif
{
#ifdef ACC_MPU6500_ALIGN
acc.accAlign = ACC_MPU6500_ALIGN;
acc.dev.accAlign = ACC_MPU6500_ALIGN;
#endif
accHardware = ACC_MPU6500;
break;
@ -404,10 +344,10 @@ retry:
case ACC_ICM20689:
#ifdef USE_ACC_SPI_ICM20689
if (icm20689SpiAccDetect(&acc.dev))
if (icm20689SpiAccDetect(dev))
{
#ifdef ACC_ICM20689_ALIGN
acc.accAlign = ACC_ICM20689_ALIGN;
acc.dev.accAlign = ACC_ICM20689_ALIGN;
#endif
accHardware = ACC_ICM20689;
break;
@ -416,7 +356,7 @@ retry:
; // fallthrough
case ACC_FAKE:
#ifdef USE_FAKE_ACC
if (fakeAccDetect(&acc.dev)) {
if (fakeAccDetect(dev)) {
accHardware = ACC_FAKE;
break;
}
@ -446,7 +386,7 @@ retry:
}
#ifdef BARO
static bool detectBaro(baroSensor_e baroHardwareToUse)
static bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
{
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
@ -476,7 +416,7 @@ static bool detectBaro(baroSensor_e baroHardwareToUse)
; // fallthough
case BARO_BMP085:
#ifdef USE_BARO_BMP085
if (bmp085Detect(bmp085Config, &baro.dev)) {
if (bmp085Detect(bmp085Config, dev)) {
baroHardware = BARO_BMP085;
break;
}
@ -484,7 +424,7 @@ static bool detectBaro(baroSensor_e baroHardwareToUse)
; // fallthough
case BARO_MS5611:
#ifdef USE_BARO_MS5611
if (ms5611Detect(&baro.dev)) {
if (ms5611Detect(dev)) {
baroHardware = BARO_MS5611;
break;
}
@ -492,7 +432,7 @@ static bool detectBaro(baroSensor_e baroHardwareToUse)
; // fallthough
case BARO_BMP280:
#if defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)
if (bmp280Detect(&baro.dev)) {
if (bmp280Detect(dev)) {
baroHardware = BARO_BMP280;
break;
}
@ -514,7 +454,7 @@ static bool detectBaro(baroSensor_e baroHardwareToUse)
#endif
#ifdef MAG
static bool detectMag(magSensor_e magHardwareToUse)
static bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
{
magSensor_e magHardware;
@ -547,7 +487,7 @@ static bool detectMag(magSensor_e magHardwareToUse)
retry:
mag.magAlign = ALIGN_DEFAULT;
mag.dev.magAlign = ALIGN_DEFAULT;
switch(magHardwareToUse) {
case MAG_DEFAULT:
@ -555,9 +495,9 @@ retry:
case MAG_HMC5883:
#ifdef USE_MAG_HMC5883
if (hmc5883lDetect(&mag.dev, hmc5883Config)) {
if (hmc5883lDetect(dev, hmc5883Config)) {
#ifdef MAG_HMC5883_ALIGN
mag.magAlign = MAG_HMC5883_ALIGN;
mag.dev.magAlign = MAG_HMC5883_ALIGN;
#endif
magHardware = MAG_HMC5883;
break;
@ -567,9 +507,9 @@ retry:
case MAG_AK8975:
#ifdef USE_MAG_AK8975
if (ak8975Detect(&mag.dev)) {
if (ak8975Detect(dev)) {
#ifdef MAG_AK8975_ALIGN
mag.magAlign = MAG_AK8975_ALIGN;
mag.dev.magAlign = MAG_AK8975_ALIGN;
#endif
magHardware = MAG_AK8975;
break;
@ -579,9 +519,9 @@ retry:
case MAG_AK8963:
#ifdef USE_MAG_AK8963
if (ak8963Detect(&mag.dev)) {
if (ak8963Detect(dev)) {
#ifdef MAG_AK8963_ALIGN
mag.magAlign = MAG_AK8963_ALIGN;
mag.dev.magAlign = MAG_AK8963_ALIGN;
#endif
magHardware = MAG_AK8963;
break;
@ -611,7 +551,7 @@ retry:
#endif
#ifdef SONAR
static bool detectSonar(void)
static bool sonarDetect(void)
{
if (feature(FEATURE_SONAR)) {
// the user has set the sonar feature, so assume they have an HC-SR04 plugged in,
@ -623,23 +563,10 @@ static bool detectSonar(void)
}
#endif
static void reconfigureAlignment(const sensorAlignmentConfig_t *sensorAlignmentConfig)
{
if (sensorAlignmentConfig->gyro_align != ALIGN_DEFAULT) {
gyro.gyroAlign = sensorAlignmentConfig->gyro_align;
}
if (sensorAlignmentConfig->acc_align != ALIGN_DEFAULT) {
acc.accAlign = sensorAlignmentConfig->acc_align;
}
if (sensorAlignmentConfig->mag_align != ALIGN_DEFAULT) {
mag.magAlign = sensorAlignmentConfig->mag_align;
}
}
bool sensorsAutodetect(const sensorAlignmentConfig_t *sensorAlignmentConfig,
const sensorSelectionConfig_t *sensorSelectionConfig,
int16_t magDeclinationFromConfig,
const gyroConfig_t *gyroConfig,
bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
const accelerometerConfig_t *accelerometerConfig,
const compassConfig_t *compassConfig,
const barometerConfig_t *barometerConfig,
const sonarConfig_t *sonarConfig)
{
memset(&acc, 0, sizeof(acc));
@ -653,7 +580,7 @@ bool sensorsAutodetect(const sensorAlignmentConfig_t *sensorAlignmentConfig,
UNUSED(mpuDetectionResult);
#endif
if (!detectGyro()) {
if (!gyroDetect(&gyro.dev)) {
return false;
}
@ -664,7 +591,7 @@ bool sensorsAutodetect(const sensorAlignmentConfig_t *sensorAlignmentConfig,
gyro.dev.init(&gyro.dev); // driver initialisation
gyroInit(gyroConfig); // sensor initialisation
if (detectAcc(sensorSelectionConfig->acc_hardware)) {
if (accDetect(&acc.dev, accelerometerConfig->acc_hardware)) {
acc.dev.acc_1G = 256; // set default
acc.dev.init(&acc.dev); // driver initialisation
accInit(gyro.targetLooptime); // sensor initialisation
@ -674,30 +601,40 @@ bool sensorsAutodetect(const sensorAlignmentConfig_t *sensorAlignmentConfig,
mag.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.
#ifdef MAG
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
if (detectMag(sensorSelectionConfig->mag_hardware)) {
if (compassDetect(&mag.dev, compassConfig->mag_hardware)) {
// calculate magnetic declination
const int16_t deg = magDeclinationFromConfig / 100;
const int16_t min = magDeclinationFromConfig % 100;
const int16_t deg = compassConfig->mag_declination / 100;
const int16_t min = compassConfig->mag_declination % 100;
mag.magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
compassInit();
}
#else
UNUSED(magDeclinationFromConfig);
UNUSED(compassConfig);
#endif
#ifdef BARO
detectBaro(sensorSelectionConfig->baro_hardware);
baroDetect(&baro.dev, barometerConfig->baro_hardware);
#else
UNUSED(barometerConfig);
#endif
#ifdef SONAR
if (detectSonar()) {
if (sonarDetect()) {
sonarInit(sonarConfig);
}
#else
UNUSED(sonarConfig);
#endif
reconfigureAlignment(sensorAlignmentConfig);
if (gyroConfig->gyro_align != ALIGN_DEFAULT) {
gyro.dev.gyroAlign = gyroConfig->gyro_align;
}
if (accelerometerConfig->acc_align != ALIGN_DEFAULT) {
acc.dev.accAlign = accelerometerConfig->acc_align;
}
if (compassConfig->mag_align != ALIGN_DEFAULT) {
mag.dev.magAlign = compassConfig->mag_align;
}
return true;
}

View File

@ -17,12 +17,8 @@
#pragma once
struct sensorAlignmentConfig_s;
struct sensorSelectionConfig_s;
struct gyroConfig_s;
struct sonarConfig_s;
bool sensorsAutodetect(const struct sensorAlignmentConfig_s *sensorAlignmentConfig,
const struct sensorSelectionConfig_s *sensorSelectionConfig,
int16_t magDeclinationFromConfig,
const struct gyroConfig_s *gyroConfig,
const struct sonarConfig_s *sonarConfig);
bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
const accelerometerConfig_t *accConfig,
const compassConfig_t *compassConfig,
const barometerConfig_t *baroConfig,
const sonarConfig_t *sonarConfig);

View File

@ -49,34 +49,5 @@ typedef enum {
SENSOR_MAG = 1 << 3,
SENSOR_SONAR = 1 << 4,
SENSOR_GPS = 1 << 5,
SENSOR_GPSMAG = 1 << 6,
SENSOR_GPSMAG = 1 << 6
} sensors_e;
typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1,
CW90_DEG = 2,
CW180_DEG = 3,
CW270_DEG = 4,
CW0_DEG_FLIP = 5,
CW90_DEG_FLIP = 6,
CW180_DEG_FLIP = 7,
CW270_DEG_FLIP = 8
} sensor_align_e;
typedef struct sensorAlignmentConfig_s {
sensor_align_e gyro_align; // gyro alignment
sensor_align_e acc_align; // acc alignment
sensor_align_e mag_align; // mag alignment
} sensorAlignmentConfig_t;
typedef struct sensorSelectionConfig_s {
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
uint8_t baro_hardware; // Barometer hardware to use
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
} sensorSelectionConfig_t;
typedef struct sensorTrims_s {
flightDynamicsTrims_t accZero;
flightDynamicsTrims_t magZero;
} sensorTrims_t;

View File

@ -47,7 +47,7 @@ void targetConfiguration(master_t *config)
{
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->sensorSelectionConfig.mag_hardware = MAG_NONE; // disabled by default
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.minthrottle = 1000;

View File

@ -58,7 +58,7 @@ void targetConfiguration(master_t *config)
{
config->batteryConfig.currentMeterOffset = CURRENTOFFSET;
config->batteryConfig.currentMeterScale = CURRENTSCALE;
config->sensorSelectionConfig.mag_hardware = MAG_NONE; // disabled by default
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.minthrottle = 1000;

View File

@ -44,7 +44,6 @@
#define MPU_INT_EXTI PC13
#define USE_EXTI
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define REMAP_TIM16_DMA
#define REMAP_TIM17_DMA

View File

@ -31,8 +31,8 @@
void targetConfiguration(master_t *config)
{
if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) {
config->sensorAlignmentConfig.gyro_align = CW180_DEG;
config->sensorAlignmentConfig.acc_align = CW180_DEG;
config->gyroConfig.gyro_align = CW180_DEG;
config->accelerometerConfig.acc_align = CW180_DEG;
config->beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
}

View File

@ -144,7 +144,6 @@
#define USE_ADC
#define VBAT_ADC_PIN PC3
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define LED_STRIP

View File

@ -48,7 +48,7 @@ void targetConfiguration(master_t *config)
config->boardAlignment.pitchDegrees = 10;
//config->rcControlsConfig.deadband = 10;
//config->rcControlsConfig.yaw_deadband = 10;
config->sensorSelectionConfig.mag_hardware = 1;
config->compassConfig.mag_hardware = 1;
config->profile[0].controlRateProfile[0].dynThrPID = 45;
config->profile[0].controlRateProfile[0].tpa_breakpoint = 1700;

View File

@ -26,8 +26,7 @@
#define USBD_SERIALNUMBER_STRING "0x8020000"
#endif
#define PLL_M 16
#define PLL_N 336
#define TARGET_XTAL_MHZ 16
#define LED0 PC14
#define LED1 PC13

View File

@ -36,8 +36,7 @@
typedef enum BSTDevice {
BSTDEV_1,
BSTDEV_2,
BSTDEV_MAX = BSTDEV_2,
BSTDEV_2
} BSTDevice;
void bstInit(BSTDevice index);

View File

@ -125,7 +125,6 @@
#define ENSURE_MPU_DATA_READY_IS_LOW
#define LED_STRIP
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM

View File

@ -161,7 +161,6 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define REMAP_TIM17_DMA

View File

@ -175,7 +175,6 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define TARGET_IO_PORTA 0xffff

View File

@ -46,7 +46,6 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define REMAP_TIM17_DMA

View File

@ -23,7 +23,6 @@
#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define USE_ESCSERIAL

View File

@ -46,7 +46,6 @@
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define USE_SPI

View File

@ -34,6 +34,6 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MOTOR, 1 ), // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 1 ), // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
DEF_TIM(TIM17, CH1, PA7, TIM_USE_PPM, 0 ), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0 ), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0 ), // LED - PB8 - *TIM16_CH1, TIM4_CH3, TIM8_CH2
};

View File

@ -34,7 +34,7 @@
#define MPU_INT_EXTI PA15
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO
#define ACC
@ -55,12 +55,6 @@
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_INSTANCE SPI2
//#define BARO
//#define USE_BARO_MS5611
//#define MAG
//#define USE_MAG_HMC5883
#define USE_VCP
#define USE_UART1
#define USE_UART2
@ -87,7 +81,6 @@
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
#define SENSORS_SET (SENSOR_ACC)
#undef GPS
@ -102,7 +95,6 @@
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define SPEKTRUM_BIND
@ -115,9 +107,6 @@
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
// #define TARGET_IO_PORTF (BIT(0)|BIT(1))
// !!TODO - check the following line is correct
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View File

@ -4,7 +4,5 @@ FEATURES = VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6050.c \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c
drivers/accgyro_spi_mpu6000.c

View File

@ -40,8 +40,9 @@
#include "config/config_master.h"
// alternative defaults settings for MULTIFLITEPICO targets
void targetConfiguration(master_t *config) {
config->sensorSelectionConfig.mag_hardware = MAG_NONE; // disabled by default
void targetConfiguration(master_t *config)
{
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
config->batteryConfig.vbatscale = 100;
config->batteryConfig.vbatresdivval = 15;

View File

@ -105,7 +105,6 @@
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define REMAP_TIM17_DMA

View File

@ -133,7 +133,6 @@
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
#define USE_DSHOT
#define USE_ESC_TELEMETRY
// DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative

View File

@ -160,7 +160,6 @@
#define VBAT_ADC_PIN PC2
//#define RSSI_ADC_PIN PA0
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define LED_STRIP

View File

@ -116,8 +116,6 @@
#define TARGET_IO_PORTC (BIT(5))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USE_DSHOT
#if defined(USE_UART3_RX_DMA) && defined(USE_DSHOT)
#undef USE_UART3_RX_DMA
#endif

View File

@ -41,7 +41,6 @@
#endif
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define LED0 PB5

View File

@ -35,7 +35,6 @@
#define INVERTER PC6
#define INVERTER_USART USART6
#define USE_DSHOT
#define USE_ESC_TELEMETRY
// MPU9250 interrupt

View File

@ -115,7 +115,6 @@
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define REMAP_TIM17_DMA

View File

@ -169,7 +169,6 @@
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define LED_STRIP

View File

@ -7,8 +7,8 @@ TARGET_SRC = \
drivers/accgyro_l3gd20.c \
drivers/accgyro_l3g4200d.c \
drivers/accgyro_lsm303dlhc.c \
drivers/compass_hmc5883l.c \
drivers/accgyro_adxl345.c \
drivers/accgyro_fake.c \
drivers/accgyro_bma280.c \
drivers/accgyro_mma845x.c \
drivers/accgyro_mpu.c \
@ -20,9 +20,11 @@ TARGET_SRC = \
drivers/accgyro_spi_mpu9250.c \
drivers/barometer_bmp085.c \
drivers/barometer_bmp280.c \
drivers/barometer_fake.c \
drivers/barometer_ms5611.c \
drivers/compass_ak8963.c \
drivers/compass_ak8975.c \
drivers/compass_fake.c \
drivers/compass_hmc5883l.c \
drivers/flash_m25p16.c \
drivers/max7456.c

View File

@ -0,0 +1,56 @@
/*
* 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 "drivers/io.h"
#include "drivers/timer.h"
#include "drivers/dma.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "io/serial.h"
#include "target.h"
#define TARGET_CPU_VOLTAGE 3.0
// set default settings to match our target
void targetConfiguration(master_t *config)
{
config->batteryConfig.currentMeterOffset = 0;
// we use an ina139, RL=0.005, Rs=30000
// V/A = (0.005 * 0.001 * 30000) * I
// rescale to 1/10th mV / A -> * 1000 * 10
// we use 3.0V as cpu and adc voltage -> rescale by 3.0/3.3
config->batteryConfig.currentMeterScale = (0.005 * 0.001 * 30000) * 1000 * 10 * (TARGET_CPU_VOLTAGE / 3.3);
// we use the same uart for frsky telemetry and SBUS, both non inverted
int index = findSerialPortIndexByIdentifier(SBUS_TELEMETRY_UART);
config->serialConfig.portConfigs[index].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
config->rxConfig.serialrx_provider = SERIALRX_SBUS;
config->telemetryConfig.telemetry_inversion = 0;
config->rxConfig.sbus_inversion = 0;
intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT, &config->enabledFeatures);
}

View File

@ -0,0 +1,35 @@
/*
* 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 "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA1_CH5
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA2_CH1
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA1_CH7
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), //DMA1_CH1
DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, TIMER_OUTPUT_ENABLED) //DMA1_CH2 - LED
};

View File

@ -0,0 +1,121 @@
/*
* 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/>.
*/
#pragma once
#define USB_VCP_ENABLED 1
#define TARGET_BOARD_IDENTIFIER "TFSH" // http://fishpepper.de/projects/tinyFISH
#define LED0 PC14
#define LED1 PC15
#define BEEPER PB2
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT
#define MPU6000_SPI_INSTANCE SPI1
#define MPU6000_CS_PIN PA4
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG_FLIP
#if USB_VCP_ENABLED
#define USE_VCP
#define USB_IO
#define USBD_PRODUCT_STRING "tinyFISH"
#define SERIAL_PORT_COUNT 4
#else
#define SERIAL_PORT_COUNT 3
#endif
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7
#define UART2_TX_PIN PA14
#define UART2_RX_PIN PA15
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define SBUS_TELEMETRY_UART SERIAL_PORT_USART2
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define M25P16_CS_PIN SPI2_NSS_PIN
#define M25P16_SPI_INSTANCE SPI2
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PB1
#define CURRENT_METER_ADC_PIN PB0
#define ADC_INSTANCE ADC3
#define VBAT_SCALE_DEFAULT 100
#define LED_STRIP
#define WS2811_PIN PA8
#define WS2811_TIMER TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_TELEMETRY)
#define TARGET_CONFIG
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 5
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(4) | TIM_N(8))

View File

@ -0,0 +1,7 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/flash_m25p16.c \
drivers/accgyro_spi_mpu6000.c

View File

@ -101,7 +101,6 @@
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define USE_DSHOT
#define USE_ESC_TELEMETRY
#define REMAP_TIM17_DMA

Some files were not shown because too many files have changed in this diff Show More