mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 22:05:17 +03:00
Merge remote-tracking branch 'multiwii/master' into
project-structure-alternative Conflicts: src/sensors.c
This commit is contained in:
commit
3c1ba729b9
5 changed files with 30 additions and 27 deletions
|
@ -269,10 +269,12 @@ static void getEstimatedAttitude(void)
|
||||||
accMag = accMag * 100 / ((int32_t)acc_1G * acc_1G);
|
accMag = accMag * 100 / ((int32_t)acc_1G * acc_1G);
|
||||||
|
|
||||||
rotateV(&EstG.V, deltaGyroAngle);
|
rotateV(&EstG.V, deltaGyroAngle);
|
||||||
if (sensors(SENSOR_MAG))
|
if (sensors(SENSOR_MAG)) {
|
||||||
rotateV(&EstM.V, deltaGyroAngle);
|
rotateV(&EstM.V, deltaGyroAngle);
|
||||||
else
|
} else {
|
||||||
rotateV(&EstN.V, deltaGyroAngle);
|
rotateV(&EstN.V, deltaGyroAngle);
|
||||||
|
normalizeV(&EstN.V, &EstN.V);
|
||||||
|
}
|
||||||
|
|
||||||
// Apply complimentary filter (Gyro drift correction)
|
// Apply complimentary filter (Gyro drift correction)
|
||||||
// If accel magnitude >1.15G or <0.85G and ACC vector outside of the limit range => we neutralize the effect of accelerometers in the angle estimation.
|
// If accel magnitude >1.15G or <0.85G and ACC vector outside of the limit range => we neutralize the effect of accelerometers in the angle estimation.
|
||||||
|
@ -315,7 +317,7 @@ static void getEstimatedAttitude(void)
|
||||||
int angle = lrintf(acosf(cosZ) * throttleAngleScale);
|
int angle = lrintf(acosf(cosZ) * throttleAngleScale);
|
||||||
if (angle > 900)
|
if (angle > 900)
|
||||||
angle = 900;
|
angle = 900;
|
||||||
throttleAngleCorrection = lrintf(cfg.throttle_correction_value * sinf(angle / 900.0f * M_PI / 2.0f)) ;
|
throttleAngleCorrection = lrintf(cfg.throttle_correction_value * sinf(angle / (900.0f * M_PI / 2.0f))) ;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
19
src/mw.c
19
src/mw.c
|
@ -60,11 +60,11 @@ uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
|
||||||
uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
||||||
|
|
||||||
// Automatic ACC Offset Calibration
|
// Automatic ACC Offset Calibration
|
||||||
|
bool AccInflightCalibrationArmed = false;
|
||||||
|
bool AccInflightCalibrationMeasurementDone = false;
|
||||||
|
bool AccInflightCalibrationSavetoEEProm = false;
|
||||||
|
bool AccInflightCalibrationActive = false;
|
||||||
uint16_t InflightcalibratingA = 0;
|
uint16_t InflightcalibratingA = 0;
|
||||||
int16_t AccInflightCalibrationArmed;
|
|
||||||
uint16_t AccInflightCalibrationMeasurementDone = 0;
|
|
||||||
uint16_t AccInflightCalibrationSavetoEEProm = 0;
|
|
||||||
uint16_t AccInflightCalibrationActive = 0;
|
|
||||||
|
|
||||||
void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
|
void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
|
||||||
{
|
{
|
||||||
|
@ -558,8 +558,8 @@ void loop(void)
|
||||||
// Inflight ACC Calibration
|
// Inflight ACC Calibration
|
||||||
} else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_HI)) {
|
} else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_HI)) {
|
||||||
if (AccInflightCalibrationMeasurementDone) { // trigger saving into eeprom after landing
|
if (AccInflightCalibrationMeasurementDone) { // trigger saving into eeprom after landing
|
||||||
AccInflightCalibrationMeasurementDone = 0;
|
AccInflightCalibrationMeasurementDone = false;
|
||||||
AccInflightCalibrationSavetoEEProm = 1;
|
AccInflightCalibrationSavetoEEProm = true;
|
||||||
} else {
|
} else {
|
||||||
AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
|
AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
|
||||||
if (AccInflightCalibrationArmed) {
|
if (AccInflightCalibrationArmed) {
|
||||||
|
@ -621,14 +621,15 @@ void loop(void)
|
||||||
if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
|
if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
|
||||||
if (AccInflightCalibrationArmed && f.ARMED && rcData[THROTTLE] > mcfg.mincheck && !rcOptions[BOXARM]) { // Copter is airborne and you are turning it off via boxarm : start measurement
|
if (AccInflightCalibrationArmed && f.ARMED && rcData[THROTTLE] > mcfg.mincheck && !rcOptions[BOXARM]) { // Copter is airborne and you are turning it off via boxarm : start measurement
|
||||||
InflightcalibratingA = 50;
|
InflightcalibratingA = 50;
|
||||||
AccInflightCalibrationArmed = 0;
|
AccInflightCalibrationArmed = false;
|
||||||
}
|
}
|
||||||
if (rcOptions[BOXCALIB]) { // Use the Calib Option to activate : Calib = TRUE Meausrement started, Land and Calib = 0 measurement stored
|
if (rcOptions[BOXCALIB]) { // Use the Calib Option to activate : Calib = TRUE Meausrement started, Land and Calib = 0 measurement stored
|
||||||
if (!AccInflightCalibrationActive && !AccInflightCalibrationMeasurementDone)
|
if (!AccInflightCalibrationActive && !AccInflightCalibrationMeasurementDone)
|
||||||
InflightcalibratingA = 50;
|
InflightcalibratingA = 50;
|
||||||
|
AccInflightCalibrationActive = true;
|
||||||
} else if (AccInflightCalibrationMeasurementDone && !f.ARMED) {
|
} else if (AccInflightCalibrationMeasurementDone && !f.ARMED) {
|
||||||
AccInflightCalibrationMeasurementDone = 0;
|
AccInflightCalibrationMeasurementDone = false;
|
||||||
AccInflightCalibrationSavetoEEProm = 1;
|
AccInflightCalibrationSavetoEEProm = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -4,10 +4,10 @@
|
||||||
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
|
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
|
||||||
|
|
||||||
extern uint16_t InflightcalibratingA;
|
extern uint16_t InflightcalibratingA;
|
||||||
extern int16_t AccInflightCalibrationArmed;
|
extern bool AccInflightCalibrationArmed;
|
||||||
extern uint16_t AccInflightCalibrationMeasurementDone;
|
extern bool AccInflightCalibrationMeasurementDone;
|
||||||
extern uint16_t AccInflightCalibrationSavetoEEProm;
|
extern bool AccInflightCalibrationSavetoEEProm;
|
||||||
extern uint16_t AccInflightCalibrationActive;
|
extern bool AccInflightCalibrationActive;
|
||||||
|
|
||||||
void ACC_Common(void)
|
void ACC_Common(void)
|
||||||
{
|
{
|
||||||
|
@ -62,8 +62,8 @@ void ACC_Common(void)
|
||||||
}
|
}
|
||||||
// all values are measured
|
// all values are measured
|
||||||
if (InflightcalibratingA == 1) {
|
if (InflightcalibratingA == 1) {
|
||||||
AccInflightCalibrationActive = 0;
|
AccInflightCalibrationActive = false;
|
||||||
AccInflightCalibrationMeasurementDone = 1;
|
AccInflightCalibrationMeasurementDone = true;
|
||||||
toggleBeep = 2; // buzzer for indicatiing the end of calibration
|
toggleBeep = 2; // buzzer for indicatiing the end of calibration
|
||||||
// recover saved values to maintain current flight behavior until new values are transferred
|
// recover saved values to maintain current flight behavior until new values are transferred
|
||||||
mcfg.accZero[ROLL] = accZero_saved[ROLL];
|
mcfg.accZero[ROLL] = accZero_saved[ROLL];
|
||||||
|
@ -75,8 +75,8 @@ void ACC_Common(void)
|
||||||
InflightcalibratingA--;
|
InflightcalibratingA--;
|
||||||
}
|
}
|
||||||
// Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration
|
// Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration
|
||||||
if (AccInflightCalibrationSavetoEEProm == 1) { // the copter is landed, disarmed and the combo has been done again
|
if (AccInflightCalibrationSavetoEEProm) { // the copter is landed, disarmed and the combo has been done again
|
||||||
AccInflightCalibrationSavetoEEProm = 0;
|
AccInflightCalibrationSavetoEEProm = false;
|
||||||
mcfg.accZero[ROLL] = b[ROLL] / 50;
|
mcfg.accZero[ROLL] = b[ROLL] / 50;
|
||||||
mcfg.accZero[PITCH] = b[PITCH] / 50;
|
mcfg.accZero[PITCH] = b[PITCH] / 50;
|
||||||
mcfg.accZero[YAW] = b[YAW] / 50 - acc_1G; // for nunchuk 200=1G
|
mcfg.accZero[YAW] = b[YAW] / 50 - acc_1G; // for nunchuk 200=1G
|
||||||
|
|
|
@ -4,7 +4,7 @@
|
||||||
** File : stm32_flash.ld
|
** File : stm32_flash.ld
|
||||||
**
|
**
|
||||||
** Abstract : Linker script for STM32F103C8 Device with
|
** Abstract : Linker script for STM32F103C8 Device with
|
||||||
** 64KByte FLASH, 20KByte RAM
|
** 128KByte FLASH, 20KByte RAM
|
||||||
**
|
**
|
||||||
*****************************************************************************
|
*****************************************************************************
|
||||||
*/
|
*/
|
||||||
|
@ -13,7 +13,7 @@
|
||||||
ENTRY(Reset_Handler)
|
ENTRY(Reset_Handler)
|
||||||
|
|
||||||
/* Highest address of the user mode stack */
|
/* Highest address of the user mode stack */
|
||||||
_estack = 0x20005000; /* end of 10K RAM */
|
_estack = 0x20005000; /* end of 20K RAM */
|
||||||
|
|
||||||
/* Generate a link error if heap and stack don't fit into RAM */
|
/* Generate a link error if heap and stack don't fit into RAM */
|
||||||
_Min_Heap_Size = 0; /* required amount of heap */
|
_Min_Heap_Size = 0; /* required amount of heap */
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue