1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-21 07:15:16 +03:00

Remove all trailing whitespaces in .c and .h files

This commit is contained in:
Michel Pastor 2018-08-06 15:54:20 +02:00
parent 24398b124d
commit c949d19725
56 changed files with 174 additions and 174 deletions

View file

@ -1027,7 +1027,7 @@ static void writeSlowFrame(void)
blackboxWriteUnsignedVB(slowHistory.powerSupplyImpedance); blackboxWriteUnsignedVB(slowHistory.powerSupplyImpedance);
blackboxWriteUnsignedVB(slowHistory.sagCompensatedVBat); blackboxWriteUnsignedVB(slowHistory.sagCompensatedVBat);
blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT); blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT);
blackboxSlowFrameIterationTimer = 0; blackboxSlowFrameIterationTimer = 0;

View file

@ -31,12 +31,12 @@ typedef struct {
} fpQuaternion_t; } fpQuaternion_t;
static inline fpQuaternion_t * quaternionInitUnit(fpQuaternion_t * result) static inline fpQuaternion_t * quaternionInitUnit(fpQuaternion_t * result)
{ {
result->q0 = 1.0f; result->q0 = 1.0f;
result->q1 = 0.0f; result->q1 = 0.0f;
result->q2 = 0.0f; result->q2 = 0.0f;
result->q3 = 0.0f; result->q3 = 0.0f;
return result; return result;
} }
static inline fpQuaternion_t * quaternionInitFromVector(fpQuaternion_t * result, const fpVector3_t * v) static inline fpQuaternion_t * quaternionInitFromVector(fpQuaternion_t * result, const fpVector3_t * v)

View file

@ -42,7 +42,7 @@ void rotationMatrixFromAngles(fpMat3_t * rmat, const fp_angles_t * angles);
void rotationMatrixFromAxisAngle(fpMat3_t * rmat, const fpAxisAngle_t * a); void rotationMatrixFromAxisAngle(fpMat3_t * rmat, const fpAxisAngle_t * a);
static inline void vectorZero(fpVector3_t * v) static inline void vectorZero(fpVector3_t * v)
{ {
v->x = 0.0f; v->x = 0.0f;
v->y = 0.0f; v->y = 0.0f;
v->z = 0.0f; v->z = 0.0f;
@ -61,7 +61,7 @@ static inline fpVector3_t * rotationMatrixRotateVector(fpVector3_t * result, con
} }
static inline float vectorNormSquared(const fpVector3_t * v) static inline float vectorNormSquared(const fpVector3_t * v)
{ {
return sq(v->x) + sq(v->y) + sq(v->z); return sq(v->x) + sq(v->y) + sq(v->z);
} }

View file

@ -62,7 +62,7 @@ const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t
} }
} }
DEBUG_TRACE("GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X", DEBUG_TRACE("GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X",
desiredLpf, desiredRateHz, desiredLpf, desiredRateHz,
candidate->gyroLpf, candidate->gyroRateHz, candidate->gyroLpf, candidate->gyroRateHz,
candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]); candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]);

View file

@ -153,13 +153,13 @@ static void bmi160AccAndGyroInit(gyroDev_t *gyro)
busWrite(gyro->busDev, BMI160_REG_ACC_RANGE, BMI160_RANGE_8G); busWrite(gyro->busDev, BMI160_REG_ACC_RANGE, BMI160_RANGE_8G);
delay(1); delay(1);
busWrite(gyro->busDev, BMI160_REG_GYR_RANGE, BMI160_RANGE_2000DPS); busWrite(gyro->busDev, BMI160_REG_GYR_RANGE, BMI160_RANGE_2000DPS);
delay(1); delay(1);
// Enable offset compensation // Enable offset compensation
// uint8_t val = spiBusReadRegister(bus, BMI160_REG_OFFSET_0); // uint8_t val = spiBusReadRegister(bus, BMI160_REG_OFFSET_0);
// busWrite(gyro->busDev, BMI160_REG_OFFSET_0, val | 0xC0); // busWrite(gyro->busDev, BMI160_REG_OFFSET_0, val | 0xC0);
// Enable data ready interrupt // Enable data ready interrupt
busWrite(gyro->busDev, BMI160_REG_INT_EN1, BMI160_INT_EN1_DRDY); busWrite(gyro->busDev, BMI160_REG_INT_EN1, BMI160_INT_EN1_DRDY);

View file

@ -130,7 +130,7 @@ bool l3g4200dDetect(gyroDev_t *gyro)
if (gyro->busDev == NULL) { if (gyro->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(gyro->busDev)) { if (!deviceDetect(gyro->busDev)) {
busDeviceDeInit(gyro->busDev); busDeviceDeInit(gyro->busDev);
return false; return false;

View file

@ -105,7 +105,7 @@ bool l3gd20Detect(gyroDev_t *gyro)
if (gyro->busDev == NULL) { if (gyro->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(gyro->busDev)) { if (!deviceDetect(gyro->busDev)) {
busDeviceDeInit(gyro->busDev); busDeviceDeInit(gyro->busDev);
return false; return false;

View file

@ -138,7 +138,7 @@
#define MPU_DLPF_188HZ 0x01 #define MPU_DLPF_188HZ 0x01
#define MPU_DLPF_256HZ 0x00 #define MPU_DLPF_256HZ 0x00
typedef struct mpuConfiguration_s { typedef struct mpuConfiguration_s {
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
} mpuConfiguration_t; } mpuConfiguration_t;

View file

@ -121,7 +121,7 @@ bool mpu3050Detect(gyroDev_t *gyro)
if (gyro->busDev == NULL) { if (gyro->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(gyro->busDev)) { if (!deviceDetect(gyro->busDev)) {
busDeviceDeInit(gyro->busDev); busDeviceDeInit(gyro->busDev);
return false; return false;

View file

@ -162,7 +162,7 @@ static bool mpu6000DeviceDetect(busDevice_t * busDev)
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
busWrite(busDev, MPU_RA_PWR_MGMT_1, BIT_H_RESET); busWrite(busDev, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
do { do {
delay(150); delay(150);

View file

@ -118,7 +118,7 @@ static bool mpu6500DeviceDetect(busDevice_t * dev)
busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busSetSpeed(dev, BUS_SPEED_INITIALIZATION);
busWrite(dev, MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET); busWrite(dev, MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET);
do { do {
delay(150); delay(150);

View file

@ -62,7 +62,7 @@ typedef enum {
BUSTYPE_SPI = 2 BUSTYPE_SPI = 2
} busType_e; } busType_e;
/* Ultimately all hardware descriptors will go to target definition files. /* Ultimately all hardware descriptors will go to target definition files.
* Driver code will merely query for it's HW descriptor and initialize it */ * Driver code will merely query for it's HW descriptor and initialize it */
typedef enum { typedef enum {
DEVHW_NONE = 0, DEVHW_NONE = 0,
@ -166,8 +166,8 @@ typedef struct busDevice_s {
#endif #endif
} busdev; } busdev;
IO_t irqPin; // Device IRQ pin. Bus system will only assign IO_t object to this var. Initialization is up to device driver IO_t irqPin; // Device IRQ pin. Bus system will only assign IO_t object to this var. Initialization is up to device driver
uint32_t scratchpad[BUS_SCRATCHPAD_MEMORY_SIZE / sizeof(uint32_t)]; // Memory where device driver can store persistent data. Zeroed out when initializing the device uint32_t scratchpad[BUS_SCRATCHPAD_MEMORY_SIZE / sizeof(uint32_t)]; // Memory where device driver can store persistent data. Zeroed out when initializing the device
// for the first time. Useful when once device is shared between several sensors // for the first time. Useful when once device is shared between several sensors
// (like MPU/ICM acc-gyro sensors) // (like MPU/ICM acc-gyro sensors)
} busDevice_t; } busDevice_t;
@ -251,7 +251,7 @@ bool spiBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data);
bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length); bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length);
bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data); bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data);
/* Pre-initialize all known device descriptors to make sure hardware state is consistent and known /* Pre-initialize all known device descriptors to make sure hardware state is consistent and known
* Initialize bus hardware */ * Initialize bus hardware */
void busInit(void); void busInit(void);

View file

@ -73,14 +73,14 @@
#endif #endif
#if defined(STM32F3) #if defined(STM32F3)
static const uint16_t spiDivisorMapFast[] = { static const uint16_t spiDivisorMapFast[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 281.25 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 281.25 KBits/s
SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 562.5 KBits/s SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 562.5 KBits/s
SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 9.0 MBits/s SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 9.0 MBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 18.0 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 18.0 MBits/s
SPI_BaudRatePrescaler_4 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s SPI_BaudRatePrescaler_4 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s
}; };
static const uint16_t spiDivisorMapSlow[] = { static const uint16_t spiDivisorMapSlow[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 140.625 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 140.625 KBits/s
SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 562.5 KBits/s SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 562.5 KBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 9.0 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 9.0 MBits/s
@ -88,14 +88,14 @@ static const uint16_t spiDivisorMapSlow[] = {
SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s
}; };
#elif defined(STM32F4) #elif defined(STM32F4)
static const uint16_t spiDivisorMapFast[] = { static const uint16_t spiDivisorMapFast[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 328.125 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 328.125 KBits/s
SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 656.25 KBits/s SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 656.25 KBits/s
SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 10.5 MBits/s SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 10.5 MBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 21.0 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 21.0 MBits/s
SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 42.0 MBits/s SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 42.0 MBits/s
}; };
static const uint16_t spiDivisorMapSlow[] = { static const uint16_t spiDivisorMapSlow[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 164.062 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 164.062 KBits/s
SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 656.25 KBits/s SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 656.25 KBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 10.5 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 10.5 MBits/s

View file

@ -39,7 +39,7 @@
typedef enum { typedef enum {
SPI_CLOCK_INITIALIZATON = 0, // Lowest possible SPI_CLOCK_INITIALIZATON = 0, // Lowest possible
SPI_CLOCK_SLOW = 1, // ~1 MHz SPI_CLOCK_SLOW = 1, // ~1 MHz
SPI_CLOCK_STANDARD = 2, // ~10MHz SPI_CLOCK_STANDARD = 2, // ~10MHz
SPI_CLOCK_FAST = 3, // ~20MHz SPI_CLOCK_FAST = 3, // ~20MHz
SPI_CLOCK_ULTRAFAST = 4 // Highest possible SPI_CLOCK_ULTRAFAST = 4 // Highest possible

View file

@ -68,14 +68,14 @@
#define SPI4_NSS_PIN NONE #define SPI4_NSS_PIN NONE
#endif #endif
static const uint16_t spiDivisorMapFast[] = { static const uint16_t spiDivisorMapFast[] = {
SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 421.875 KBits/s SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 421.875 KBits/s
SPI_BAUDRATEPRESCALER_128, // SPI_CLOCK_SLOW 843.75 KBits/s SPI_BAUDRATEPRESCALER_128, // SPI_CLOCK_SLOW 843.75 KBits/s
SPI_BAUDRATEPRESCALER_16, // SPI_CLOCK_STANDARD 6.75 MBits/s SPI_BAUDRATEPRESCALER_16, // SPI_CLOCK_STANDARD 6.75 MBits/s
SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_FAST 13.5 MBits/s SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_FAST 13.5 MBits/s
SPI_BAUDRATEPRESCALER_4 // SPI_CLOCK_ULTRAFAST 27.0 MBits/s SPI_BAUDRATEPRESCALER_4 // SPI_CLOCK_ULTRAFAST 27.0 MBits/s
}; };
static const uint16_t spiDivisorMapSlow[] = { static const uint16_t spiDivisorMapSlow[] = {
SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 210.937 KBits/s SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 210.937 KBits/s
SPI_BAUDRATEPRESCALER_64, // SPI_CLOCK_SLOW 843.75 KBits/s SPI_BAUDRATEPRESCALER_64, // SPI_CLOCK_SLOW 843.75 KBits/s
SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_STANDARD 6.75 MBits/s SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_STANDARD 6.75 MBits/s

View file

@ -21,7 +21,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*/ */
/* /*
* This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB) * This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB)
*/ */

View file

@ -55,16 +55,16 @@ void hcsr04i2cUpdate(rangefinderDev_t *rangefinder)
uint8_t response[3]; uint8_t response[3];
isHcsr04i2cResponding = busReadBuf(rangefinder->busDev, HCSR04_I2C_REGISTRY_STATUS, response, 3); isHcsr04i2cResponding = busReadBuf(rangefinder->busDev, HCSR04_I2C_REGISTRY_STATUS, response, 3);
if (!isHcsr04i2cResponding) { if (!isHcsr04i2cResponding) {
hcsr04i2cMeasurementCm = RANGEFINDER_HARDWARE_FAILURE; hcsr04i2cMeasurementCm = RANGEFINDER_HARDWARE_FAILURE;
return; return;
} }
if (response[HCSR04_I2C_REGISTRY_STATUS] == 0) { if (response[HCSR04_I2C_REGISTRY_STATUS] == 0) {
hcsr04i2cMeasurementCm = hcsr04i2cMeasurementCm =
(int32_t)((int32_t)response[HCSR04_I2C_REGISTRY_DISTANCE_HIGH] << 8) + (int32_t)((int32_t)response[HCSR04_I2C_REGISTRY_DISTANCE_HIGH] << 8) +
response[HCSR04_I2C_REGISTRY_DISTANCE_LOW]; response[HCSR04_I2C_REGISTRY_DISTANCE_LOW];
} else { } else {
@ -105,7 +105,7 @@ bool hcsr04i2c0Detect(rangefinderDev_t *rangefinder)
if (rangefinder->busDev == NULL) { if (rangefinder->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(rangefinder->busDev)) { if (!deviceDetect(rangefinder->busDev)) {
busDeviceDeInit(rangefinder->busDev); busDeviceDeInit(rangefinder->busDev);
return false; return false;

View file

@ -117,7 +117,7 @@ static void srf10_start_reading(rangefinderDev_t * rangefinder)
isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeLowByte, &lowByte); isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeLowByte, &lowByte);
isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeHighByte, &highByte); isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeHighByte, &highByte);
srf10measurementCm = highByte << 8 | lowByte; srf10measurementCm = highByte << 8 | lowByte;
if (srf10measurementCm > SRF10_MAX_RANGE_CM) { if (srf10measurementCm > SRF10_MAX_RANGE_CM) {
@ -171,7 +171,7 @@ bool srf10Detect(rangefinderDev_t * rangefinder)
if (rangefinder->busDev == NULL) { if (rangefinder->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(rangefinder->busDev)) { if (!deviceDetect(rangefinder->busDev)) {
busDeviceDeInit(rangefinder->busDev); busDeviceDeInit(rangefinder->busDev);
return false; return false;

View file

@ -21,7 +21,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*/ */
/* /*
* This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB) * This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB)
*/ */

View file

@ -59,7 +59,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
GPIO_StructInit(&GPIO_InitStructure); GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave JTAG pins alone GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave JTAG pins alone
GPIO_Init(GPIOA, &GPIO_InitStructure); GPIO_Init(GPIOA, &GPIO_InitStructure);

View file

@ -58,7 +58,7 @@ uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
return i; return i;
} }
} }
// make sure final index is out of range // make sure final index is out of range
return ~1; return ~1;
} }

View file

@ -77,7 +77,7 @@ void vtxCommonSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t ch
if ((band > vtxDevice->capability.bandCount) || (channel > vtxDevice->capability.channelCount)) if ((band > vtxDevice->capability.bandCount) || (channel > vtxDevice->capability.channelCount))
return; return;
if (vtxDevice->vTable->setBandAndChannel) { if (vtxDevice->vTable->setBandAndChannel) {
vtxDevice->vTable->setBandAndChannel(vtxDevice, band, channel); vtxDevice->vTable->setBandAndChannel(vtxDevice, band, channel);
} }
@ -91,7 +91,7 @@ void vtxCommonSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
if (index > vtxDevice->capability.powerCount) if (index > vtxDevice->capability.powerCount)
return; return;
if (vtxDevice->vTable->setPowerByIndex) { if (vtxDevice->vTable->setPowerByIndex) {
vtxDevice->vTable->setPowerByIndex(vtxDevice, index); vtxDevice->vTable->setPowerByIndex(vtxDevice, index);
} }

View file

@ -211,7 +211,7 @@ static void updateArmingStatus(void)
else { else {
DISABLE_ARMING_FLAG(ARMING_DISABLED_SYSTEM_OVERLOADED); DISABLE_ARMING_FLAG(ARMING_DISABLED_SYSTEM_OVERLOADED);
} }
#if defined(USE_NAV) #if defined(USE_NAV)
/* CHECK: Navigation safety */ /* CHECK: Navigation safety */
if (navigationBlockArming()) { if (navigationBlockArming()) {
@ -243,7 +243,7 @@ static void updateArmingStatus(void)
/* CHECK: */ /* CHECK: */
if (!isHardwareHealthy()) { if (!isHardwareHealthy()) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE); ENABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE);
} }
else { else {
DISABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE); DISABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE);
} }
@ -276,7 +276,7 @@ static void updateArmingStatus(void)
/* CHECK: Do not allow arming if Servo AutoTrim is enabled */ /* CHECK: Do not allow arming if Servo AutoTrim is enabled */
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
} }
else { else {
DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
} }

View file

@ -199,7 +199,7 @@ void init(void)
// Re-initialize system clock to their final values (if necessary) // Re-initialize system clock to their final values (if necessary)
systemClockSetup(systemConfig()->cpuUnderclock); systemClockSetup(systemConfig()->cpuUnderclock);
i2cSetSpeed(systemConfig()->i2c_speed); i2cSetSpeed(systemConfig()->i2c_speed);
#ifdef USE_HARDWARE_PREBOOT_SETUP #ifdef USE_HARDWARE_PREBOOT_SETUP

View file

@ -1046,7 +1046,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif #endif
#ifdef USE_ACC_NOTCH #ifdef USE_ACC_NOTCH
sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz); sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz);
sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff); sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff);
#else #else
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
@ -1054,9 +1054,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif #endif
#ifdef USE_GYRO_BIQUAD_RC_FIR2 #ifdef USE_GYRO_BIQUAD_RC_FIR2
sbufWriteU16(dst, gyroConfig()->gyro_stage2_lowpass_hz); sbufWriteU16(dst, gyroConfig()->gyro_stage2_lowpass_hz);
#else #else
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
#endif #endif
break; break;
@ -1846,7 +1846,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
gyroConfigMutable()->gyro_soft_notch_cutoff_2 = constrain(sbufReadU16(src), 1, 500); gyroConfigMutable()->gyro_soft_notch_cutoff_2 = constrain(sbufReadU16(src), 1, 500);
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
#endif #endif
#ifdef USE_ACC_NOTCH #ifdef USE_ACC_NOTCH
if (dataSize >= 21) { if (dataSize >= 21) {
@ -1854,14 +1854,14 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
accelerometerConfigMutable()->acc_notch_cutoff = constrain(sbufReadU16(src), 1, 255); accelerometerConfigMutable()->acc_notch_cutoff = constrain(sbufReadU16(src), 1, 255);
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
#endif #endif
#ifdef USE_GYRO_BIQUAD_RC_FIR2 #ifdef USE_GYRO_BIQUAD_RC_FIR2
if (dataSize >= 22) { if (dataSize >= 22) {
gyroConfigMutable()->gyro_stage2_lowpass_hz = constrain(sbufReadU16(src), 0, 500); gyroConfigMutable()->gyro_stage2_lowpass_hz = constrain(sbufReadU16(src), 0, 500);
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
#endif #endif
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
break; break;

View file

@ -128,6 +128,6 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)
if (FLIGHT_MODE(NAV_LAUNCH_MODE)) if (FLIGHT_MODE(NAV_LAUNCH_MODE))
return FLM_LAUNCH; return FLM_LAUNCH;
return FLM_ACRO; return FLM_ACRO;
} }

View file

@ -44,8 +44,8 @@ typedef enum {
ARMING_DISABLED_OOM = (1 << 25), ARMING_DISABLED_OOM = (1 << 25),
ARMING_DISABLED_INVALID_SETTING = (1 << 26), ARMING_DISABLED_INVALID_SETTING = (1 << 26),
ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED |
ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED | ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED |
ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_BOXKILLSWITCH | ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_BOXKILLSWITCH |
ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU |
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING) ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING)

View file

@ -77,7 +77,7 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
.failsafe_fw_pitch_angle = 100, // 10 deg dive (yes, positive means dive) .failsafe_fw_pitch_angle = 100, // 10 deg dive (yes, positive means dive)
.failsafe_fw_yaw_rate = -45, // 45 deg/s left yaw (left is negative, 8s for full turn) .failsafe_fw_yaw_rate = -45, // 45 deg/s left yaw (left is negative, 8s for full turn)
.failsafe_stick_motion_threshold = 50, .failsafe_stick_motion_threshold = 50,
.failsafe_min_distance = 0, // No minimum distance for failsafe by default .failsafe_min_distance = 0, // No minimum distance for failsafe by default
.failsafe_min_distance_procedure = FAILSAFE_PROCEDURE_DROP_IT // default minimum distance failsafe procedure .failsafe_min_distance_procedure = FAILSAFE_PROCEDURE_DROP_IT // default minimum distance failsafe procedure
); );
@ -400,7 +400,7 @@ void failsafeUpdateState(void)
// Craft is closer than minimum failsafe procedure distance (if set to non-zero) // Craft is closer than minimum failsafe procedure distance (if set to non-zero)
// GPS must also be working, and home position set // GPS must also be working, and home position set
if ((failsafeConfig()->failsafe_min_distance > 0) && if ((failsafeConfig()->failsafe_min_distance > 0) &&
((GPS_distanceToHome * 100) < failsafeConfig()->failsafe_min_distance) && ((GPS_distanceToHome * 100) < failsafeConfig()->failsafe_min_distance) &&
sensors(SENSOR_GPS) && STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) { sensors(SENSOR_GPS) && STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
// Use the alternate, minimum distance failsafe procedure instead // Use the alternate, minimum distance failsafe procedure instead

View file

@ -507,9 +507,9 @@ static void imuCalculateEstimatedAttitude(float dT)
fpVector3_t measuredMagBF = { .v = { mag.magADC[X], mag.magADC[Y], mag.magADC[Z] } }; fpVector3_t measuredMagBF = { .v = { mag.magADC[X], mag.magADC[Y], mag.magADC[Z] } };
imuMahonyAHRSupdate(dT, &imuMeasuredRotationBF, imuMahonyAHRSupdate(dT, &imuMeasuredRotationBF,
useAcc ? &imuMeasuredAccelBF : NULL, useAcc ? &imuMeasuredAccelBF : NULL,
useMag ? &measuredMagBF : NULL, useMag ? &measuredMagBF : NULL,
useCOG, courseOverGround); useCOG, courseOverGround);
imuUpdateEulerAngles(); imuUpdateEulerAngles();

View file

@ -155,7 +155,7 @@ void mixerUsePWMIOConfiguration(void)
currentMixer[i] = *customMotorMixer(i); currentMixer[i] = *customMotorMixer(i);
motorCount++; motorCount++;
} }
// in 3D mode, mixer gain has to be halved // in 3D mode, mixer gain has to be halved
if (feature(FEATURE_3D)) { if (feature(FEATURE_3D)) {
if (motorCount > 1) { if (motorCount > 1) {

View file

@ -112,7 +112,7 @@ static uint16_t estimateRTHAltitudeChangeEnergy(float altitudeChange, float vert
} }
// returns distance in m // returns distance in m
// *heading is in degrees // *heading is in degrees
static float estimateRTHDistanceAndHeadingAfterAltitudeChange(float altitudeChange, float horizontalWindSpeed, float windHeading, float verticalWindSpeed, float *heading) { static float estimateRTHDistanceAndHeadingAfterAltitudeChange(float altitudeChange, float horizontalWindSpeed, float windHeading, float verticalWindSpeed, float *heading) {
float estimatedAltitudeChangeGroundDistance = estimateRTHAltitudeChangeGroundDistance(altitudeChange, horizontalWindSpeed, windHeading, verticalWindSpeed); float estimatedAltitudeChangeGroundDistance = estimateRTHAltitudeChangeGroundDistance(altitudeChange, horizontalWindSpeed, windHeading, verticalWindSpeed);
if (navConfig()->general.flags.rth_climb_first && (altitudeChange > 0)) { if (navConfig()->general.flags.rth_climb_first && (altitudeChange > 0)) {

View file

@ -231,7 +231,7 @@ void servoMixer(float dT)
input[INPUT_STABILIZED_YAW] = axisPID[YAW]; input[INPUT_STABILIZED_YAW] = axisPID[YAW];
// Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter // Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter
if (feature(FEATURE_3D) && (rcData[THROTTLE] < PWM_RANGE_MIDDLE) && if (feature(FEATURE_3D) && (rcData[THROTTLE] < PWM_RANGE_MIDDLE) &&
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) { (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) {
input[INPUT_STABILIZED_YAW] *= -1; input[INPUT_STABILIZED_YAW] *= -1;
} }

View file

@ -126,12 +126,12 @@ static const uint8_t beep_hardwareFailure[] = {
10, 10, BEEPER_COMMAND_STOP 10, 10, BEEPER_COMMAND_STOP
}; };
// Cam connection opened // Cam connection opened
static const uint8_t beep_camOpenBeep[] = { static const uint8_t beep_camOpenBeep[] = {
5, 15, 10, 15, 20, BEEPER_COMMAND_STOP 5, 15, 10, 15, 20, BEEPER_COMMAND_STOP
}; };
// Cam connection close // Cam connection close
static const uint8_t beep_camCloseBeep[] = { static const uint8_t beep_camCloseBeep[] = {
10, 8, 5, BEEPER_COMMAND_STOP 10, 8, 5, BEEPER_COMMAND_STOP
}; };

View file

@ -43,8 +43,8 @@ typedef enum {
BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on
BEEPER_USB, // Some boards have beeper powered USB connected BEEPER_USB, // Some boards have beeper powered USB connected
BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled
BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated
BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop
BEEPER_ALL, // Turn ON or OFF all beeper conditions BEEPER_ALL, // Turn ON or OFF all beeper conditions
BEEPER_PREFERENCE, // Save preferred beeper configuration BEEPER_PREFERENCE, // Save preferred beeper configuration

View file

@ -129,7 +129,7 @@ static bool cxofOpflowUpdate(opflowData_t * data)
bufferPtr = 0; bufferPtr = 0;
} }
} }
if (newPacket) { if (newPacket) {
*data = tmpData; *data = tmpData;
} }

View file

@ -122,7 +122,7 @@ static uint8_t runcamDeviceReceivePacket(runcamDevice_t *device, uint8_t command
if (!runcamDeviceIsResponseReceiveDone(command, data, dataPos, &isDone)) { if (!runcamDeviceIsResponseReceiveDone(command, data, dataPos, &isDone)) {
return 0; return 0;
} }
if (isDone) { if (isDone) {
responseDataLen = dataPos; responseDataLen = dataPos;
break; break;
@ -184,11 +184,11 @@ static void runcamDeviceSendPacket(runcamDevice_t *device, uint8_t command, uint
static bool runcamDeviceSendRequestAndWaitingResp(runcamDevice_t *device, uint8_t commandID, uint8_t *paramData, uint8_t paramDataLen, uint8_t *outputBuffer, uint8_t *outputBufferLen) static bool runcamDeviceSendRequestAndWaitingResp(runcamDevice_t *device, uint8_t commandID, uint8_t *paramData, uint8_t paramDataLen, uint8_t *outputBuffer, uint8_t *outputBufferLen)
{ {
int max_retries = 1; int max_retries = 1;
// here using 1000ms as timeout, because the response from 5 key simulation command need a long time about >= 600ms, // here using 1000ms as timeout, because the response from 5 key simulation command need a long time about >= 600ms,
// so set a max value to ensure we can receive the response // so set a max value to ensure we can receive the response
int timeoutMs = 1000; int timeoutMs = 1000;
// only the command sending on initializing step need retry logic, // only the command sending on initializing step need retry logic,
// otherwise, the timeout of 1000 ms is enough for the response from device // otherwise, the timeout of 1000 ms is enough for the response from device
if (commandID == RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO) { if (commandID == RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO) {
max_retries = 3; max_retries = 3;
@ -256,7 +256,7 @@ static void sendCtrlCommand(runcamDevice_t *device, rcsplit_ctrl_argument_e argu
// get the device info(firmware version, protocol version and features, see the // get the device info(firmware version, protocol version and features, see the
// definition of runcamDeviceInfo_t to know more) // definition of runcamDeviceInfo_t to know more)
static bool runcamDeviceGetDeviceInfo(runcamDevice_t *device, uint8_t *outputBuffer) static bool runcamDeviceGetDeviceInfo(runcamDevice_t *device, uint8_t *outputBuffer)
{ {
// Send "who are you" command to device to detect the device whether is running RCSplit FW1.0 or RCSplit FW1.1 // Send "who are you" command to device to detect the device whether is running RCSplit FW1.0 or RCSplit FW1.1
uint32_t max_retries = 3; uint32_t max_retries = 3;
@ -303,7 +303,7 @@ static bool runcamDeviceGetDeviceInfo(runcamDevice_t *device, uint8_t *outputBuf
} }
} }
return runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, NULL, 0, outputBuffer, NULL); return runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, NULL, 0, outputBuffer, NULL);
} }
static bool runcamDeviceSend5KeyOSDCableConnectionEvent(runcamDevice_t *device, uint8_t operation, uint8_t *outActionID, uint8_t *outErrorCode) static bool runcamDeviceSend5KeyOSDCableConnectionEvent(runcamDevice_t *device, uint8_t operation, uint8_t *outActionID, uint8_t *outErrorCode)
@ -434,13 +434,13 @@ static bool runcamDeviceDecodeSettingDetail(sbuf_t *buf, runcamDeviceSettingDeta
outSettingDetail->stepSize = sbufReadU8(buf); outSettingDetail->stepSize = sbufReadU8(buf);
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_UINT16: case RCDEVICE_PROTOCOL_SETTINGTYPE_UINT16:
case RCDEVICE_PROTOCOL_SETTINGTYPE_INT16: case RCDEVICE_PROTOCOL_SETTINGTYPE_INT16:
outSettingDetail->value = sbufReadU16(buf); outSettingDetail->value = sbufReadU16(buf);
outSettingDetail->minValue = sbufReadU16(buf); outSettingDetail->minValue = sbufReadU16(buf);
outSettingDetail->maxValue = sbufReadU16(buf); outSettingDetail->maxValue = sbufReadU16(buf);
outSettingDetail->stepSize = sbufReadU8(buf); outSettingDetail->stepSize = sbufReadU8(buf);
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_FLOAT: case RCDEVICE_PROTOCOL_SETTINGTYPE_FLOAT:
outSettingDetail->value = sbufReadU32(buf); outSettingDetail->value = sbufReadU32(buf);
outSettingDetail->minValue = sbufReadU32(buf); outSettingDetail->minValue = sbufReadU32(buf);
outSettingDetail->maxValue = sbufReadU32(buf); outSettingDetail->maxValue = sbufReadU32(buf);
@ -470,7 +470,7 @@ static bool runcamDeviceDecodeSettingDetail(sbuf_t *buf, runcamDeviceSettingDeta
result = strtok_r(NULL, delims, &saveptr); result = strtok_r(NULL, delims, &saveptr);
i++; i++;
} }
} }
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_STRING: { case RCDEVICE_PROTOCOL_SETTINGTYPE_STRING: {
const char *tmp = (const char *)sbufConstPtr(buf); const char *tmp = (const char *)sbufConstPtr(buf);
@ -478,7 +478,7 @@ static bool runcamDeviceDecodeSettingDetail(sbuf_t *buf, runcamDeviceSettingDeta
sbufAdvance(buf, strlen(tmp) + 1); sbufAdvance(buf, strlen(tmp) + 1);
outSettingDetail->maxStringSize = sbufReadU8(buf); outSettingDetail->maxStringSize = sbufReadU8(buf);
} }
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_FOLDER: case RCDEVICE_PROTOCOL_SETTINGTYPE_FOLDER:
break; break;
@ -586,7 +586,7 @@ bool runcamDeviceWriteSetting(runcamDevice_t *device, uint8_t settingID, const v
} }
memset(response, 0, sizeof(runcamDeviceWriteSettingResponse_t)); memset(response, 0, sizeof(runcamDeviceWriteSettingResponse_t));
response->resultCode = 1; // initialize the result code to failed response->resultCode = 1; // initialize the result code to failed
uint8_t paramsBufLen = sizeof(uint8_t) + paramDataLen; uint8_t paramsBufLen = sizeof(uint8_t) + paramDataLen;
uint8_t paramsBuf[RCDEVICE_PROTOCOL_MAX_DATA_SIZE]; uint8_t paramsBuf[RCDEVICE_PROTOCOL_MAX_DATA_SIZE];

View file

@ -81,9 +81,9 @@ typedef enum {
} rcdevice_5key_simulation_operation_e; } rcdevice_5key_simulation_operation_e;
// Operation of RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION // Operation of RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION
typedef enum { typedef enum {
RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN = 0x01, RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN = 0x01,
RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE = 0x02 RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE = 0x02
} RCDEVICE_5key_connection_event_e; } RCDEVICE_5key_connection_event_e;
typedef enum { typedef enum {

View file

@ -2720,9 +2720,9 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
// If we were in LAUNCH mode - force switch to IDLE only if the throttle is low // If we were in LAUNCH mode - force switch to IDLE only if the throttle is low
if (FLIGHT_MODE(NAV_LAUNCH_MODE)) { if (FLIGHT_MODE(NAV_LAUNCH_MODE)) {
throttleStatus_e throttleStatus = calculateThrottleStatus(); throttleStatus_e throttleStatus = calculateThrottleStatus();
if (throttleStatus != THROTTLE_LOW) if (throttleStatus != THROTTLE_LOW)
return NAV_FSM_EVENT_NONE; return NAV_FSM_EVENT_NONE;
else else
return NAV_FSM_EVENT_SWITCH_TO_IDLE; return NAV_FSM_EVENT_SWITCH_TO_IDLE;
} }
} }

View file

@ -492,7 +492,7 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
} }
rxFlightChannelsValid = true; rxFlightChannelsValid = true;
// Read and process channel data // Read and process channel data
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) { for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
const uint8_t rawChannel = calculateChannelRemapping(rxConfig()->rcmap, REMAPPABLE_CHANNEL_COUNT, channel); const uint8_t rawChannel = calculateChannelRemapping(rxConfig()->rcmap, REMAPPABLE_CHANNEL_COUNT, channel);

View file

@ -195,7 +195,7 @@ void opflowUpdate(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_FLOW_RAW, 3, RADIANS_TO_DEGREES(opflow.bodyRate[Y])); DEBUG_SET(DEBUG_FLOW_RAW, 3, RADIANS_TO_DEGREES(opflow.bodyRate[Y]));
} }
else { else {
// Opflow updated but invalid - zero out flow rates and body // Opflow updated but invalid - zero out flow rates and body
opflow.flowRate[X] = 0; opflow.flowRate[X] = 0;
opflow.flowRate[Y] = 0; opflow.flowRate[Y] = 0;

View file

@ -59,7 +59,7 @@ typedef struct opflow_s {
float bodyRate[2]; // body inertial angular rate in rad/sec measured about the X and Y body axis float bodyRate[2]; // body inertial angular rate in rad/sec measured about the X and Y body axis
float gyroBodyRateAcc[2]; float gyroBodyRateAcc[2];
timeUs_t gyroBodyRateTimeUs; timeUs_t gyroBodyRateTimeUs;
uint8_t rawQuality; uint8_t rawQuality;
} opflow_t; } opflow_t;

View file

@ -61,7 +61,7 @@ rangefinder_t rangefinder;
#define RANGEFINDER_HARDWARE_TIMEOUT_MS 500 // Accept 500ms of non-responsive sensor, report HW failure otherwise #define RANGEFINDER_HARDWARE_TIMEOUT_MS 500 // Accept 500ms of non-responsive sensor, report HW failure otherwise
#define RANGEFINDER_DYNAMIC_THRESHOLD 600 //Used to determine max. usable rangefinder disatance #define RANGEFINDER_DYNAMIC_THRESHOLD 600 //Used to determine max. usable rangefinder disatance
#define RANGEFINDER_DYNAMIC_FACTOR 75 #define RANGEFINDER_DYNAMIC_FACTOR 75
#ifdef USE_RANGEFINDER #ifdef USE_RANGEFINDER
PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 1); PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 1);

View file

@ -12,7 +12,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this software. If not, see <http://www.gnu.org/licenses/>. * along with this software. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once
@ -70,7 +70,7 @@
#define USE_SPI_DEVICE_3 #define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10 #define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11 #define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PB5 #define SPI3_MOSI_PIN PB5
#define USE_OSD #define USE_OSD
@ -107,7 +107,7 @@
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS #define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define USE_PITOT_MS4525 #define USE_PITOT_MS4525
#define PITOT_I2C_BUS DEFAULT_I2C_BUS #define PITOT_I2C_BUS DEFAULT_I2C_BUS
//USART //USART
#define USE_VCP #define USE_VCP
@ -145,9 +145,9 @@
#define ADC_CHANNEL_3_PIN PA0 #define ADC_CHANNEL_3_PIN PA0
#define VBAT_ADC_CHANNEL ADC_CHN_1 #define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 #define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3 #define RSSI_ADC_CHANNEL ADC_CHN_3
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_OSD) #define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_OSD)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -44,7 +44,7 @@ void targetConfiguration(void)
{ {
systemConfigMutable()->asyncMode = ASYNC_MODE_NONE; systemConfigMutable()->asyncMode = ASYNC_MODE_NONE;
mixerConfigMutable()->platformType = PLATFORM_MULTIROTOR; mixerConfigMutable()->platformType = PLATFORM_MULTIROTOR;
featureSet(FEATURE_VBAT); featureSet(FEATURE_VBAT);
featureSet(FEATURE_GPS); featureSet(FEATURE_GPS);
featureSet(FEATURE_TELEMETRY); featureSet(FEATURE_TELEMETRY);
@ -58,58 +58,58 @@ void targetConfiguration(void)
serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_NONE; // UART4 serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_NONE; // UART4
serialConfigMutable()->portConfigs[4].functionMask = FUNCTION_TELEMETRY_MAVLINK; // UART5 serialConfigMutable()->portConfigs[4].functionMask = FUNCTION_TELEMETRY_MAVLINK; // UART5
gyroConfigMutable()->looptime = 1000; gyroConfigMutable()->looptime = 1000;
gyroConfigMutable()->gyroSync = 1; gyroConfigMutable()->gyroSync = 1;
gyroConfigMutable()->gyro_lpf = 0; // 256 Hz gyroConfigMutable()->gyro_lpf = 0; // 256 Hz
gyroConfigMutable()->gyro_soft_lpf_hz = 90; gyroConfigMutable()->gyro_soft_lpf_hz = 90;
gyroConfigMutable()->gyro_soft_notch_hz_1 = 150; gyroConfigMutable()->gyro_soft_notch_hz_1 = 150;
gyroConfigMutable()->gyro_soft_notch_cutoff_1 = 80; gyroConfigMutable()->gyro_soft_notch_cutoff_1 = 80;
accelerometerConfigMutable()->acc_hardware = ACC_MPU6500; accelerometerConfigMutable()->acc_hardware = ACC_MPU6500;
accelerometerConfigMutable()->acc_lpf_hz = 15; accelerometerConfigMutable()->acc_lpf_hz = 15;
compassConfigMutable()->mag_hardware = MAG_HMC5883; compassConfigMutable()->mag_hardware = MAG_HMC5883;
compassConfigMutable()->mag_align = CW270_DEG_FLIP; compassConfigMutable()->mag_align = CW270_DEG_FLIP;
barometerConfigMutable()->baro_hardware = BARO_MS5607; barometerConfigMutable()->baro_hardware = BARO_MS5607;
barometerConfigMutable()->use_median_filtering = 1; barometerConfigMutable()->use_median_filtering = 1;
rxConfigMutable()->receiverType = RX_TYPE_SERIAL; rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
rxConfigMutable()->serialrx_provider = SERIALRX_IBUS; rxConfigMutable()->serialrx_provider = SERIALRX_IBUS;
rxConfigMutable()->mincheck = 1100; rxConfigMutable()->mincheck = 1100;
rxConfigMutable()->maxcheck = 1900; rxConfigMutable()->maxcheck = 1900;
blackboxConfigMutable()->rate_num = 1; blackboxConfigMutable()->rate_num = 1;
blackboxConfigMutable()->rate_denom = 4; blackboxConfigMutable()->rate_denom = 4;
motorConfigMutable()->minthrottle = 1015; motorConfigMutable()->minthrottle = 1015;
motorConfigMutable()->maxthrottle = 2000; motorConfigMutable()->maxthrottle = 2000;
motorConfigMutable()->mincommand = 980; motorConfigMutable()->mincommand = 980;
motorConfigMutable()->motorPwmRate = 2000; motorConfigMutable()->motorPwmRate = 2000;
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_ONESHOT125; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_ONESHOT125;
failsafeConfigMutable()->failsafe_delay = 5; failsafeConfigMutable()->failsafe_delay = 5;
failsafeConfigMutable()->failsafe_recovery_delay = 5; failsafeConfigMutable()->failsafe_recovery_delay = 5;
failsafeConfigMutable()->failsafe_off_delay = 200; failsafeConfigMutable()->failsafe_off_delay = 200;
failsafeConfigMutable()->failsafe_throttle = 1200; failsafeConfigMutable()->failsafe_throttle = 1200;
failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_RTH; failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_RTH;
boardAlignmentMutable()->rollDeciDegrees = 0; boardAlignmentMutable()->rollDeciDegrees = 0;
boardAlignmentMutable()->pitchDeciDegrees = 165; boardAlignmentMutable()->pitchDeciDegrees = 165;
boardAlignmentMutable()->yawDeciDegrees = 0; boardAlignmentMutable()->yawDeciDegrees = 0;
mixerConfigMutable()->yaw_jump_prevention_limit = 200; mixerConfigMutable()->yaw_jump_prevention_limit = 200;
imuConfigMutable()->small_angle = 30; imuConfigMutable()->small_angle = 30;
gpsConfigMutable()->provider = GPS_UBLOX; gpsConfigMutable()->provider = GPS_UBLOX;
gpsConfigMutable()->sbasMode = SBAS_NONE; gpsConfigMutable()->sbasMode = SBAS_NONE;
gpsConfigMutable()->dynModel = GPS_DYNMODEL_AIR_1G; gpsConfigMutable()->dynModel = GPS_DYNMODEL_AIR_1G;
gpsConfigMutable()->autoConfig = 1; gpsConfigMutable()->autoConfig = 1;
gpsConfigMutable()->autoBaud = 1; gpsConfigMutable()->autoBaud = 1;
gpsConfigMutable()->gpsMinSats = 7; gpsConfigMutable()->gpsMinSats = 7;
rcControlsConfigMutable()->deadband = 10; rcControlsConfigMutable()->deadband = 10;
rcControlsConfigMutable()->yaw_deadband = 15; rcControlsConfigMutable()->yaw_deadband = 15;
@ -117,17 +117,17 @@ void targetConfiguration(void)
navConfigMutable()->general.flags.use_thr_mid_for_althold = 1; navConfigMutable()->general.flags.use_thr_mid_for_althold = 1;
navConfigMutable()->general.flags.extra_arming_safety = 1; navConfigMutable()->general.flags.extra_arming_safety = 1;
navConfigMutable()->general.flags.rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS; navConfigMutable()->general.flags.rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS;
navConfigMutable()->general.max_auto_speed = 500; navConfigMutable()->general.max_auto_speed = 500;
navConfigMutable()->general.max_auto_climb_rate = 200; navConfigMutable()->general.max_auto_climb_rate = 200;
navConfigMutable()->general.max_manual_speed = 500; navConfigMutable()->general.max_manual_speed = 500;
navConfigMutable()->general.max_manual_climb_rate = 200; navConfigMutable()->general.max_manual_climb_rate = 200;
navConfigMutable()->general.rth_altitude = 1000; navConfigMutable()->general.rth_altitude = 1000;
navConfigMutable()->mc.max_bank_angle = 30; navConfigMutable()->mc.max_bank_angle = 30;
navConfigMutable()->mc.hover_throttle = 1500; navConfigMutable()->mc.hover_throttle = 1500;
navConfigMutable()->mc.auto_disarm_delay = 2000; navConfigMutable()->mc.auto_disarm_delay = 2000;
/* /*
aux 0 0 0 1150 2100 aux 0 0 0 1150 2100
aux 1 2 0 1300 1700 aux 1 2 0 1300 1700
@ -151,7 +151,7 @@ void targetConfiguration(void)
configureModeActivationCondition(3, BOXNAVPOSHOLD, 3, 1300, 1700); configureModeActivationCondition(3, BOXNAVPOSHOLD, 3, 1300, 1700);
configureModeActivationCondition(4, BOXNAVRTH, 3, 1700, 2100); configureModeActivationCondition(4, BOXNAVRTH, 3, 1700, 2100);
configureModeActivationCondition(5, BOXANGLE, 3, 1700, 2100); configureModeActivationCondition(5, BOXANGLE, 3, 1700, 2100);
// Rates and PIDs // Rates and PIDs
setConfigProfile(0); setConfigProfile(0);
pidProfileMutable()->bank_mc.pid[PID_PITCH].P = 65; pidProfileMutable()->bank_mc.pid[PID_PITCH].P = 65;
@ -166,7 +166,7 @@ void targetConfiguration(void)
pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20; pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10; pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75;
pidProfileMutable()->max_angle_inclination[FD_ROLL] = 300; pidProfileMutable()->max_angle_inclination[FD_ROLL] = 300;
pidProfileMutable()->max_angle_inclination[FD_PITCH] = 300; pidProfileMutable()->max_angle_inclination[FD_PITCH] = 300;
pidProfileMutable()->dterm_lpf_hz = 70; pidProfileMutable()->dterm_lpf_hz = 70;

View file

@ -34,7 +34,7 @@ const timerHardware_t timerHardware[] = {
{ TIM8, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, //S4 DMA3_ST7 SV5 { TIM8, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, //S4 DMA3_ST7 SV5
{ TIM2, IO_TAG(PA15), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_LED }, //S5 DMA1_ST5 2812LED { TIM2, IO_TAG(PA15), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_LED }, //S5 DMA1_ST5 2812LED
#ifdef MATEKF405_SERVOS6 #ifdef MATEKF405_SERVOS6
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S6 DMA2_ST6 SV6 { TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S6 DMA2_ST6 SV6
#else #else

View file

@ -201,7 +201,7 @@
#define WS2811_PIN PA15 // S5 pad for iNav #define WS2811_PIN PA15 // S5 pad for iNav
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream5 #define WS2811_DMA_STREAM DMA1_Stream5
#define WS2811_DMA_CHANNEL DMA_Channel_3 #define WS2811_DMA_CHANNEL DMA_Channel_3
#define USE_SPEKTRUM_BIND #define USE_SPEKTRUM_BIND
#define BIND_PIN PA3 // RX2 #define BIND_PIN PA3 // RX2

View file

@ -135,7 +135,7 @@
#define UART6_RX_PIN PC7 #define UART6_RX_PIN PC7
#define USE_SOFTSERIAL1 //Frsky SmartPort on TX2 pad #define USE_SOFTSERIAL1 //Frsky SmartPort on TX2 pad
#define SOFTSERIAL_1_TX_PIN PA2 #define SOFTSERIAL_1_TX_PIN PA2
#define SOFTSERIAL_1_RX_PIN PA2 #define SOFTSERIAL_1_RX_PIN PA2
#define SERIAL_PORT_COUNT 8 #define SERIAL_PORT_COUNT 8
@ -160,7 +160,7 @@
#define WS2811_PIN PA15 #define WS2811_PIN PA15
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream5 #define WS2811_DMA_STREAM DMA1_Stream5
#define WS2811_DMA_CHANNEL DMA_Channel_3 #define WS2811_DMA_CHANNEL DMA_Channel_3
// *************** OTHERS ************************* // *************** OTHERS *************************
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)

View file

@ -38,7 +38,7 @@ const timerHardware_t timerHardware[] = {
{ TIM1, IO_TAG(PA8), TIM_CHANNEL_1, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF1_TIM1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S6 DMA2_ST6 SV6 { TIM1, IO_TAG(PA8), TIM_CHANNEL_1, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF1_TIM1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S6 DMA2_ST6 SV6
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF2_TIM4, TIM_USE_MC_CHNFW | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S7 DMA1_ST7 { TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF2_TIM4, TIM_USE_MC_CHNFW | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S7 DMA1_ST7
//{ TIM5, IO_TAG(PA2), TIM_CHANNEL_3, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF2_TIM5, TIM_USE_ANY }, //{ TIM5, IO_TAG(PA2), TIM_CHANNEL_3, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF2_TIM5, TIM_USE_ANY },
{ TIM2, IO_TAG(PA15), TIM_CHANNEL_1, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, TIM_USE_LED}, //2812 STRIP DMA1_ST5 { TIM2, IO_TAG(PA15), TIM_CHANNEL_1, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, TIM_USE_LED}, //2812 STRIP DMA1_ST5
}; };

View file

@ -57,7 +57,7 @@ void targetConfiguration(void)
pidProfileMutable()->bank_mc.pid[PID_YAW].D = 0; pidProfileMutable()->bank_mc.pid[PID_YAW].D = 0;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20; pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10; pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10;
pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75;
} }
#endif #endif

View file

@ -293,8 +293,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
@ -316,7 +316,7 @@
#include "stm32f4xx.h" #include "stm32f4xx.h"
#include "system_stm32f4xx.h" #include "system_stm32f4xx.h"
uint32_t hse_value = HSE_VALUE; uint32_t hse_value = HSE_VALUE;
/** /**
@ -569,10 +569,10 @@ void SystemCoreClockUpdate(void)
case 0x08: /* PLL P used as system clock source */ case 0x08: /* PLL P used as system clock source */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
SYSCLK = PLL_VCO / PLL_P SYSCLK = PLL_VCO / PLL_P
*/ */
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
if (pllsource != 0) if (pllsource != 0)
{ {
/* HSE used as PLL clock source */ /* HSE used as PLL clock source */
@ -621,10 +621,10 @@ void SystemCoreClockUpdate(void)
} }
/** /**
* @brief Configures the System clock source, PLL Multiplier and Divider factors, * @brief Configures the System clock source, PLL Multiplier and Divider factors,
* AHB/APBx prescalers and Flash settings * AHB/APBx prescalers and Flash settings
* @Note This function should be called only once the RCC clock configuration * @Note This function should be called only once the RCC clock configuration
* is reset to the default reset state (done in SystemInit() function). * is reset to the default reset state (done in SystemInit() function).
* @param None * @param None
* @retval None * @retval None
*/ */
@ -634,10 +634,10 @@ void SetSysClock(void)
/* PLL (clocked by HSE) used as System clock source */ /* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/ /******************************************************************************/
__IO uint32_t StartUpCounter = 0, HSEStatus = 0; __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* Enable HSE */ /* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON); RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */ /* Wait till HSE is ready and if Time out is reached exit */
do do
{ {
@ -666,7 +666,7 @@ void SetSysClock(void)
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
/* PCLK2 = HCLK / 2*/ /* PCLK2 = HCLK / 2*/
RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
/* PCLK1 = HCLK / 4*/ /* PCLK1 = HCLK / 4*/
RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */ #endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
@ -704,7 +704,7 @@ void SetSysClock(void)
while ((RCC->CR & RCC_CR_PLLRDY) == 0) while ((RCC->CR & RCC_CR_PLLRDY) == 0)
{ {
} }
#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx) #if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
/* Enable the Over-drive to extend the clock frequency to 180 Mhz */ /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
PWR->CR |= PWR_CR_ODEN; PWR->CR |= PWR_CR_ODEN;

View file

@ -16,7 +16,7 @@
#include "io/gps.h" #include "io/gps.h"
#include "telemetry/frsky.h" #include "telemetry/frsky.h"
uint16_t frskyGetFlightMode(void) uint16_t frskyGetFlightMode(void)
{ {
uint16_t tmpi = 0; uint16_t tmpi = 0;
@ -65,16 +65,16 @@ uint16_t frskyGetFlightMode(void)
return tmpi; return tmpi;
} }
uint16_t frskyGetGPSState(void) uint16_t frskyGetGPSState(void)
{ {
uint16_t tmpi = 0; uint16_t tmpi = 0;
// ones and tens columns (# of satellites 0 - 99) // ones and tens columns (# of satellites 0 - 99)
tmpi += constrain(gpsSol.numSat, 0, 99); tmpi += constrain(gpsSol.numSat, 0, 99);
// hundreds column (satellite accuracy HDOP: 0 = worst [HDOP > 5.5], 9 = best [HDOP <= 1.0]) // hundreds column (satellite accuracy HDOP: 0 = worst [HDOP > 5.5], 9 = best [HDOP <= 1.0])
tmpi += (9 - constrain((gpsSol.hdop - 51) / 50, 0, 9)) * 100; tmpi += (9 - constrain((gpsSol.hdop - 51) / 50, 0, 9)) * 100;
// thousands column (GPS fix status) // thousands column (GPS fix status)
if (STATE(GPS_FIX)) if (STATE(GPS_FIX))
tmpi += 1000; tmpi += 1000;
@ -82,7 +82,7 @@ uint16_t frskyGetGPSState(void)
tmpi += 2000; tmpi += 2000;
if (ARMING_FLAG(ARMED) && IS_RC_MODE_ACTIVE(BOXHOMERESET) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE)) if (ARMING_FLAG(ARMED) && IS_RC_MODE_ACTIVE(BOXHOMERESET) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE))
tmpi += 4000; tmpi += 4000;
return tmpi; return tmpi;
} }

View file

@ -203,7 +203,7 @@ void initIbusTelemetry(void) {
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE_S85, IBUS_MEAS_VALUE_STATUS); changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE_S85, IBUS_MEAS_VALUE_STATUS);
#ifdef USE_PITOT #ifdef USE_PITOT
if (sensors(SENSOR_PITOT)) changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_VSPEED, IBUS_MEAS_VALUE_VSPEED); if (sensors(SENSOR_PITOT)) changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_VSPEED, IBUS_MEAS_VALUE_VSPEED);
else else
#endif #endif
changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_PRES, IBUS_MEAS_VALUE_PRES); changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_PRES, IBUS_MEAS_VALUE_PRES);
} }
@ -223,16 +223,16 @@ void initIbusTelemetry(void) {
changeTypeIbusTelemetry(13,IBUS_MEAS_TYPE_S88, IBUS_MEAS_VALUE_GPS_LON); changeTypeIbusTelemetry(13,IBUS_MEAS_TYPE_S88, IBUS_MEAS_VALUE_GPS_LON);
changeTypeIbusTelemetry(14,IBUS_MEAS_TYPE_S89, IBUS_MEAS_VALUE_GPS_LAT); changeTypeIbusTelemetry(14,IBUS_MEAS_TYPE_S89, IBUS_MEAS_VALUE_GPS_LAT);
} }
if (type == 2 || type == 3 || type == 4 || type == 5) if (type == 2 || type == 3 || type == 4 || type == 5)
changeTypeIbusTelemetry(10, IBUS_MEAS_TYPE_GALT, IBUS_MEAS_VALUE_GALT); changeTypeIbusTelemetry(10, IBUS_MEAS_TYPE_GALT, IBUS_MEAS_VALUE_GALT);
if (type == 1 || type == 2 || type == 3 || type == 4 || type == 5) if (type == 1 || type == 2 || type == 3 || type == 4 || type == 5)
changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE_SPE, IBUS_MEAS_VALUE_SPE); changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE_SPE, IBUS_MEAS_VALUE_SPE);
if ((type == 3 || type == 4 || type == 5) && speed) if ((type == 3 || type == 4 || type == 5) && speed)
changeTypeIbusTelemetry(15,IBUS_MEAS_TYPE_SPEED, IBUS_MEAS_VALUE_SPEED); changeTypeIbusTelemetry(15,IBUS_MEAS_TYPE_SPEED, IBUS_MEAS_VALUE_SPEED);
if (type == 6) { if (type == 6) {
#ifdef USE_PITOT #ifdef USE_PITOT
if (sensors(SENSOR_PITOT)) changeTypeIbusTelemetry(9,IBUS_MEAS_TYPE1_VERTICAL_SPEED, IBUS_MEAS_VALUE_VSPEED); if (sensors(SENSOR_PITOT)) changeTypeIbusTelemetry(9,IBUS_MEAS_TYPE1_VERTICAL_SPEED, IBUS_MEAS_VALUE_VSPEED);
else else
#endif #endif
changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE1_PRES, IBUS_MEAS_VALUE_PRES); changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE1_PRES, IBUS_MEAS_VALUE_PRES);
changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE1_S85, IBUS_MEAS_VALUE_STATUS); changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE1_S85, IBUS_MEAS_VALUE_STATUS);

View file

@ -113,7 +113,7 @@ static uint8_t sendIbusMeasurement2(ibusAddress_t address, uint16_t measurement)
} }
static uint8_t sendIbusMeasurement4(ibusAddress_t address, int32_t measurement) { static uint8_t sendIbusMeasurement4(ibusAddress_t address, int32_t measurement) {
uint8_t sendBuffer[] = { 0x08, IBUS_COMMAND_MEASUREMENT | address, uint8_t sendBuffer[] = { 0x08, IBUS_COMMAND_MEASUREMENT | address,
measurement & 0xFF, (measurement >> 8) & 0xFF, (measurement >> 16) & 0xFF, (measurement >> 24) & 0xFF, measurement & 0xFF, (measurement >> 8) & 0xFF, (measurement >> 16) & 0xFF, (measurement >> 24) & 0xFF,
0x0, 0x0 }; 0x0, 0x0 };
return transmitIbusPacket(sendBuffer, sizeof sendBuffer); return transmitIbusPacket(sendBuffer, sizeof sendBuffer);
@ -167,33 +167,33 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
return sendIbusMeasurement2(address, (int16_t) (getEstimatedActualVelocity(Z))); // return sendIbusMeasurement2(address, (int16_t) (getEstimatedActualVelocity(Z))); //
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_Z) { //MAG_COURSE 0-360*, 0=north } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_Z) { //MAG_COURSE 0-360*, 0=north
return sendIbusMeasurement2(address, (uint16_t) (attitude.values.yaw * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg return sendIbusMeasurement2(address, (uint16_t) (attitude.values.yaw * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_Y) { //PITCH in } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_Y) { //PITCH in
return sendIbusMeasurement2(address, (uint16_t) (-attitude.values.pitch * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg return sendIbusMeasurement2(address, (uint16_t) (-attitude.values.pitch * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_X) { //ROLL in } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_X) { //ROLL in
return sendIbusMeasurement2(address, (uint16_t) (attitude.values.roll * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg return sendIbusMeasurement2(address, (uint16_t) (attitude.values.roll * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_VSPEED) { //Speed cm/s } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_VSPEED) { //Speed cm/s
#ifdef USE_PITOT #ifdef USE_PITOT
if (sensors(SENSOR_PITOT)) return sendIbusMeasurement2(address, (uint16_t) (pitot.airSpeed)); //int32_t if (sensors(SENSOR_PITOT)) return sendIbusMeasurement2(address, (uint16_t) (pitot.airSpeed)); //int32_t
else else
#endif #endif
return sendIbusMeasurement2(address, 0); return sendIbusMeasurement2(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ARMED) { //motorArmed } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ARMED) { //motorArmed
if ((telemetryConfig()->ibusTelemetryType & 0x7F) < 8) { if ((telemetryConfig()->ibusTelemetryType & 0x7F) < 8) {
return sendIbusMeasurement2(address, ARMING_FLAG(ARMED) ? 0 : 1); return sendIbusMeasurement2(address, ARMING_FLAG(ARMED) ? 0 : 1);
} else { } else {
return sendIbusMeasurement2(address, ARMING_FLAG(ARMED) ? 1 : 0); return sendIbusMeasurement2(address, ARMING_FLAG(ARMED) ? 1 : 0);
} }
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_MODE) { } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_MODE) {
uint16_t flightMode = flightModeToIBusTelemetryMode2[getFlightModeForTelemetry()]; uint16_t flightMode = flightModeToIBusTelemetryMode2[getFlightModeForTelemetry()];
return sendIbusMeasurement2(address, flightMode); return sendIbusMeasurement2(address, flightMode);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_PRES) { //PRESSURE in dPa -> 9876 is 987.6 hPa } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_PRES) { //PRESSURE in dPa -> 9876 is 987.6 hPa
if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (int16_t) (baro.baroPressure / 10)); //int32_t if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (int16_t) (baro.baroPressure / 10)); //int32_t
else return sendIbusMeasurement2(address, 0); else return sendIbusMeasurement2(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ALT) { //BARO_ALT in cm => m } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ALT) { //BARO_ALT in cm => m
if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (uint16_t) baro.BaroAlt); //int32_t if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (uint16_t) baro.BaroAlt); //int32_t
else return sendIbusMeasurement2(address, 0); else return sendIbusMeasurement2(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ALT4) { //BARO_ALT //In cm => m } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ALT4) { //BARO_ALT //In cm => m
if (sensors(SENSOR_BARO)) return sendIbusMeasurement4(address, (int32_t) baro.BaroAlt); //int32_t if (sensors(SENSOR_BARO)) return sendIbusMeasurement4(address, (int32_t) baro.BaroAlt); //int32_t
else return sendIbusMeasurement4(address, 0); else return sendIbusMeasurement4(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_STATUS) { //STATUS sat num AS #0, FIX AS 0, HDOP AS 0, Mode AS 0 } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_STATUS) { //STATUS sat num AS #0, FIX AS 0, HDOP AS 0, Mode AS 0
uint16_t status = flightModeToIBusTelemetryMode1[getFlightModeForTelemetry()]; uint16_t status = flightModeToIBusTelemetryMode1[getFlightModeForTelemetry()];
@ -248,12 +248,12 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
return sendIbusMeasurement4(address, 0); return sendIbusMeasurement4(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LAT1) { //GPS_LAT1 //Lattitude * 1e+7 } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LAT1) { //GPS_LAT1 //Lattitude * 1e+7
#if defined(USE_GPS) #if defined(USE_GPS)
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.llh.lat / 100000)); else if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.llh.lat / 100000)); else
#endif #endif
return sendIbusMeasurement2(address, 0); return sendIbusMeasurement2(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LON1) { //GPS_LON1 //Longitude * 1e+7 } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LON1) { //GPS_LON1 //Longitude * 1e+7
#if defined(USE_GPS) #if defined(USE_GPS)
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.llh.lon / 100000)); else if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.llh.lon / 100000)); else
#endif #endif
return sendIbusMeasurement2(address, 0); return sendIbusMeasurement2(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LAT2) { //GPS_LAT2 //Lattitude * 1e+7 } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LAT2) { //GPS_LAT2 //Lattitude * 1e+7
@ -263,7 +263,7 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
return sendIbusMeasurement2(address, 0); return sendIbusMeasurement2(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LON2) { //GPS_LON2 //Longitude * 1e+7 } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LON2) { //GPS_LON2 //Longitude * 1e+7
#if defined(USE_GPS) #if defined(USE_GPS)
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) ((gpsSol.llh.lon % 100000)/10)); else if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) ((gpsSol.llh.lon % 100000)/10)); else
#endif #endif
return sendIbusMeasurement2(address, 0); return sendIbusMeasurement2(address, 0);
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GALT4) { //GPS_ALT //In cm => m } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GALT4) { //GPS_ALT //In cm => m
@ -277,7 +277,7 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
#endif #endif
return sendIbusMeasurement2(address, 0); return sendIbusMeasurement2(address, 0);
} }
else return 0; else return 0;
} }
uint8_t respondToIbusRequest(uint8_t ibusPacket[static IBUS_RX_BUF_LEN]) { uint8_t respondToIbusRequest(uint8_t ibusPacket[static IBUS_RX_BUF_LEN]) {
@ -302,7 +302,7 @@ void changeTypeIbusTelemetry(uint8_t id, uint8_t type, uint8_t value) {
SENSOR_ADDRESS_TYPE_LOOKUP[id].type = type; SENSOR_ADDRESS_TYPE_LOOKUP[id].type = type;
SENSOR_ADDRESS_TYPE_LOOKUP[id].value = value; SENSOR_ADDRESS_TYPE_LOOKUP[id].value = value;
if (value == IBUS_MEAS_VALUE_GPS) SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 14; if (value == IBUS_MEAS_VALUE_GPS) SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 14;
else if (value == IBUS_MEAS_VALUE_GPS_LAT || value == IBUS_MEAS_VALUE_GPS_LON || value == IBUS_MEAS_VALUE_ALT4 || value == IBUS_MEAS_VALUE_GALT4) else if (value == IBUS_MEAS_VALUE_GPS_LAT || value == IBUS_MEAS_VALUE_GPS_LON || value == IBUS_MEAS_VALUE_ALT4 || value == IBUS_MEAS_VALUE_GALT4)
SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 4; SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 4;
else SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 2; else SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 2;
} }

View file

@ -35,18 +35,18 @@ typedef enum {
IBUS_MEAS_TYPE_TEMPERATURE = 0x01, //0 Temperature -##0.0 C, 0=-40.0 C, 400=0.0 C, 65535=6513.5 C IBUS_MEAS_TYPE_TEMPERATURE = 0x01, //0 Temperature -##0.0 C, 0=-40.0 C, 400=0.0 C, 65535=6513.5 C
IBUS_MEAS_TYPE_RPM = 0x02, //0 Rotation RPM, ####0RPM, 0=0RPM, 65535=65535RPM IBUS_MEAS_TYPE_RPM = 0x02, //0 Rotation RPM, ####0RPM, 0=0RPM, 65535=65535RPM
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE = 0x03, //0 External Voltage, -##0.00V, 0=0.00V, 32767=327.67V, 32768=na, 32769=-327.67V, 65535=-0.01V IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE = 0x03, //0 External Voltage, -##0.00V, 0=0.00V, 32767=327.67V, 32768=na, 32769=-327.67V, 65535=-0.01V
IBUS_MEAS_TYPE_HEADING = 0x04, //3 IBUS_MEAS_TYPE_HEADING = 0x04, //3
IBUS_MEAS_TYPE_CURRENT = 0x05, //3 IBUS_MEAS_TYPE_CURRENT = 0x05, //3
IBUS_MEAS_TYPE_CLIMB = 0x06, //3 IBUS_MEAS_TYPE_CLIMB = 0x06, //3
IBUS_MEAS_TYPE_ACC_Z = 0x07, //3 IBUS_MEAS_TYPE_ACC_Z = 0x07, //3
IBUS_MEAS_TYPE_ACC_Y = 0x08, //3 IBUS_MEAS_TYPE_ACC_Y = 0x08, //3
IBUS_MEAS_TYPE_ACC_X = 0x09, //3 IBUS_MEAS_TYPE_ACC_X = 0x09, //3
IBUS_MEAS_TYPE_VSPEED = 0x0a, //3 IBUS_MEAS_TYPE_VSPEED = 0x0a, //3
IBUS_MEAS_TYPE_SPEED = 0x0b, //3 IBUS_MEAS_TYPE_SPEED = 0x0b, //3
IBUS_MEAS_TYPE_DIST = 0x0c, //3 IBUS_MEAS_TYPE_DIST = 0x0c, //3
IBUS_MEAS_TYPE_ARMED = 0x0d, //3 IBUS_MEAS_TYPE_ARMED = 0x0d, //3
IBUS_MEAS_TYPE_MODE = 0x0e, //3 IBUS_MEAS_TYPE_MODE = 0x0e, //3
//IBUS_MEAS_TYPE_RESERVED = 0x0f, //3 //IBUS_MEAS_TYPE_RESERVED = 0x0f, //3
IBUS_MEAS_TYPE_PRES = 0x41, // Pressure, not work IBUS_MEAS_TYPE_PRES = 0x41, // Pressure, not work
//IBUS_MEAS_TYPE_ODO1 = 0x7c, // Odometer1, 0.0km, 0.0 only //IBUS_MEAS_TYPE_ODO1 = 0x7c, // Odometer1, 0.0km, 0.0 only
//IBUS_MEAS_TYPE_ODO2 = 0x7d, // Odometer2, 0.0km, 0.0 only //IBUS_MEAS_TYPE_ODO2 = 0x7d, // Odometer2, 0.0km, 0.0 only
@ -54,14 +54,14 @@ typedef enum {
IBUS_MEAS_TYPE_COG = 0x80, //3 2byte course deg * 100, 0.0..359.99 IBUS_MEAS_TYPE_COG = 0x80, //3 2byte course deg * 100, 0.0..359.99
IBUS_MEAS_TYPE_GPS_STATUS = 0x81, //3 2byte special parse byte by byte IBUS_MEAS_TYPE_GPS_STATUS = 0x81, //3 2byte special parse byte by byte
IBUS_MEAS_TYPE_GPS_LON = 0x82, //3 4byte signed WGS84 in deg * 1E7, format into %u?%02u'%02u IBUS_MEAS_TYPE_GPS_LON = 0x82, //3 4byte signed WGS84 in deg * 1E7, format into %u?%02u'%02u
IBUS_MEAS_TYPE_GPS_LAT = 0x83, //3 4byte signed WGS84 in deg * 1E7 IBUS_MEAS_TYPE_GPS_LAT = 0x83, //3 4byte signed WGS84 in deg * 1E7
IBUS_MEAS_TYPE_ALT = 0x84, //3 2byte signed barometer alt IBUS_MEAS_TYPE_ALT = 0x84, //3 2byte signed barometer alt
IBUS_MEAS_TYPE_S85 = 0x85, //3 IBUS_MEAS_TYPE_S85 = 0x85, //3
IBUS_MEAS_TYPE_S86 = 0x86, //3 IBUS_MEAS_TYPE_S86 = 0x86, //3
IBUS_MEAS_TYPE_S87 = 0x87, //3 IBUS_MEAS_TYPE_S87 = 0x87, //3
IBUS_MEAS_TYPE_S88 = 0x88, //3 IBUS_MEAS_TYPE_S88 = 0x88, //3
IBUS_MEAS_TYPE_S89 = 0x89, //3 IBUS_MEAS_TYPE_S89 = 0x89, //3
IBUS_MEAS_TYPE_S8A = 0x8A, //3 IBUS_MEAS_TYPE_S8A = 0x8A, //3
IBUS_MEAS_TYPE_GALT = 0xf9, //2 Altitude m, not work IBUS_MEAS_TYPE_GALT = 0xf9, //2 Altitude m, not work
//IBUS_MEAS_TYPE_SNR = 0xfa, // SNR, not work //IBUS_MEAS_TYPE_SNR = 0xfa, // SNR, not work
//IBUS_MEAS_TYPE_NOISE = 0xfb, // Noise, not work //IBUS_MEAS_TYPE_NOISE = 0xfb, // Noise, not work

View file

@ -454,7 +454,7 @@ void checkLtmTelemetryState(void)
if (newTelemetryEnabledValue){ if (newTelemetryEnabledValue){
configureLtmScheduler(); configureLtmScheduler();
configureLtmTelemetryPort(); configureLtmTelemetryPort();
} }
else else
freeLtmTelemetryPort(); freeLtmTelemetryPort();

View file

@ -87,7 +87,7 @@ typedef struct {
uint32_t unrepliedRequests; // 0 - all answered, 1 - request in progress, 2 or more - device failed to answer one or more requests uint32_t unrepliedRequests; // 0 - all answered, 1 - request in progress, 2 or more - device failed to answer one or more requests
uint8_t rxDataReadySize; uint8_t rxDataReadySize;
uint8_t txDataReadySize; uint8_t txDataReadySize;
uint8_t rxPacket[UIB_MAX_PACKET_SIZE]; uint8_t rxPacket[UIB_MAX_PACKET_SIZE];
uint8_t txPacket[UIB_MAX_PACKET_SIZE]; uint8_t txPacket[UIB_MAX_PACKET_SIZE];
} uavInterconnectSlot_t; } uavInterconnectSlot_t;
@ -580,7 +580,7 @@ uint8_t uibRead(uint8_t devId, uint8_t * buffer, uint8_t bufSize)
if (slot == NULL) if (slot == NULL)
return 0; return 0;
// If no READ capability - fail // If no READ capability - fail
if (!(slot->deviceFlags & UIB_FLAG_HAS_READ)) if (!(slot->deviceFlags & UIB_FLAG_HAS_READ))
return false; return false;
@ -597,7 +597,7 @@ uint8_t uibRead(uint8_t devId, uint8_t * buffer, uint8_t bufSize)
static bool slotCanWrite(const uavInterconnectSlot_t * slot) static bool slotCanWrite(const uavInterconnectSlot_t * slot)
{ {
// If no WRITE capability - fail // If no WRITE capability - fail
if (!(slot->deviceFlags & UIB_FLAG_HAS_WRITE)) if (!(slot->deviceFlags & UIB_FLAG_HAS_WRITE))
return false; return false;
@ -629,7 +629,7 @@ bool uibWrite(uint8_t devId, const uint8_t * buffer, uint8_t len)
slot->txDataReadySize = len; slot->txDataReadySize = len;
return true; return true;
} }
return false; return false;
} }
#endif #endif