mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Decouple sticks processing code from main mw loops.
Decouple led ring driver from non-driver code.
This commit is contained in:
parent
fd0b7cdf80
commit
18046013a4
16 changed files with 267 additions and 165 deletions
|
@ -26,9 +26,9 @@
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "io/rc_curves.h"
|
#include "io/rc_curves.h"
|
||||||
#include "rx/rx.h"
|
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
|
@ -538,6 +538,14 @@ void saveAndReloadCurrentProfileToCurrentProfileSlot(void)
|
||||||
readEEPROMAndNotify();
|
readEEPROMAndNotify();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void changeProfile(uint8_t profileIndex)
|
||||||
|
{
|
||||||
|
masterConfig.current_profile_index = profileIndex;
|
||||||
|
writeEEPROM();
|
||||||
|
readEEPROM();
|
||||||
|
blinkLedAndSoundBeeper(2, 40, profileIndex);
|
||||||
|
}
|
||||||
|
|
||||||
bool feature(uint32_t mask)
|
bool feature(uint32_t mask)
|
||||||
{
|
{
|
||||||
return masterConfig.enabledFeatures & mask;
|
return masterConfig.enabledFeatures & mask;
|
||||||
|
|
|
@ -34,6 +34,7 @@ void readEEPROMAndNotify(void);
|
||||||
void writeEEPROM();
|
void writeEEPROM();
|
||||||
void ensureEEPROMContainsValidData(void);
|
void ensureEEPROMContainsValidData(void);
|
||||||
void saveAndReloadCurrentProfileToCurrentProfileSlot(void);
|
void saveAndReloadCurrentProfileToCurrentProfileSlot(void);
|
||||||
|
void changeProfile(uint8_t profileIndex);
|
||||||
|
|
||||||
bool canSoftwareSerialBeUsed(void);
|
bool canSoftwareSerialBeUsed(void);
|
||||||
|
|
||||||
|
|
|
@ -10,10 +10,10 @@
|
||||||
#include "bus_i2c.h"
|
#include "bus_i2c.h"
|
||||||
|
|
||||||
// FIXME there should be no dependencies on the main source code
|
// FIXME there should be no dependencies on the main source code
|
||||||
#include "io/escservo.h"
|
//#include "io/escservo.h"
|
||||||
#include "io/rc_controls.h"
|
//#include "io/rc_controls.h"
|
||||||
#include "sensors/sensors.h"
|
//#include "sensors/sensors.h"
|
||||||
#include "flight/flight.h"
|
//#include "flight/flight.h"
|
||||||
|
|
||||||
#include "light_ledring.h"
|
#include "light_ledring.h"
|
||||||
|
|
||||||
|
@ -32,7 +32,7 @@ bool ledringDetect(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
// pitch/roll are absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
// pitch/roll are absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
||||||
void ledringState(bool armed, int16_t pitch, int16_t roll)
|
void ledringState(bool armed, int16_t pitch, int16_t roll, int16_t heading)
|
||||||
{
|
{
|
||||||
uint8_t b[10];
|
uint8_t b[10];
|
||||||
static uint8_t state;
|
static uint8_t state;
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool ledringDetect(void);
|
bool ledringDetect(void);
|
||||||
void ledringState(bool armed, int16_t pitch, int16_t roll);
|
void ledringState(bool armed, int16_t pitch, int16_t roll, int16_t heading);
|
||||||
void ledringBlink(void);
|
void ledringBlink(void);
|
||||||
|
|
|
@ -3,9 +3,9 @@
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "rx/rx.h"
|
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
|
@ -7,6 +7,7 @@
|
||||||
|
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
|
|
|
@ -28,9 +28,9 @@
|
||||||
// FIXME remove dependency on config.h
|
// FIXME remove dependency on config.h
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "rx/rx.h"
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
|
@ -11,10 +11,10 @@
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "rx/rx.h"
|
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/flight.h"
|
#include "flight/flight.h"
|
||||||
|
|
|
@ -1,15 +1,179 @@
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
|
#include "config/config.h"
|
||||||
|
#include "config/runtime_config.h"
|
||||||
|
|
||||||
|
#include "flight/flight.h"
|
||||||
|
|
||||||
|
#include "drivers/accgyro.h"
|
||||||
|
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
#include "sensors/gyro.h"
|
||||||
|
#include "sensors/acceleration.h"
|
||||||
|
|
||||||
|
#include "io/gps.h"
|
||||||
|
#include "mw.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
|
|
||||||
|
|
||||||
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
|
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
|
||||||
|
|
||||||
bool areSticksInApModePosition(uint16_t ap_mode)
|
bool areSticksInApModePosition(uint16_t ap_mode)
|
||||||
{
|
{
|
||||||
return abs(rcCommand[ROLL]) < ap_mode && abs(rcCommand[PITCH]) < ap_mode;
|
return abs(rcCommand[ROLL]) < ap_mode && abs(rcCommand[PITCH]) < ap_mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||||
|
{
|
||||||
|
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (rxConfig->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig->midrc + deadband3d_throttle)))
|
||||||
|
return THROTTLE_LOW;
|
||||||
|
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig->mincheck))
|
||||||
|
return THROTTLE_LOW;
|
||||||
|
|
||||||
|
return THROTTLE_HIGH;
|
||||||
|
}
|
||||||
|
|
||||||
|
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, uint16_t *activate, bool retarded_arm)
|
||||||
|
{
|
||||||
|
static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors
|
||||||
|
static uint8_t rcSticks; // this hold sticks position for command combos
|
||||||
|
uint8_t stTmp = 0;
|
||||||
|
int i;
|
||||||
|
|
||||||
|
// ------------------ STICKS COMMAND HANDLER --------------------
|
||||||
|
// checking sticks positions
|
||||||
|
for (i = 0; i < 4; i++) {
|
||||||
|
stTmp >>= 2;
|
||||||
|
if (rcData[i] > rxConfig->mincheck)
|
||||||
|
stTmp |= 0x80; // check for MIN
|
||||||
|
if (rcData[i] < rxConfig->maxcheck)
|
||||||
|
stTmp |= 0x40; // check for MAX
|
||||||
|
}
|
||||||
|
if (stTmp == rcSticks) {
|
||||||
|
if (rcDelayCommand < 250)
|
||||||
|
rcDelayCommand++;
|
||||||
|
} else
|
||||||
|
rcDelayCommand = 0;
|
||||||
|
rcSticks = stTmp;
|
||||||
|
|
||||||
|
// perform actions
|
||||||
|
if (throttleStatus == THROTTLE_LOW) {
|
||||||
|
if (activate[BOXARM] > 0) { // Arming/Disarming via ARM BOX
|
||||||
|
if (rcOptions[BOXARM] && f.OK_TO_ARM)
|
||||||
|
mwArm();
|
||||||
|
else if (f.ARMED)
|
||||||
|
mwDisarm();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rcDelayCommand != 20) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (f.ARMED) { // actions during armed
|
||||||
|
// Disarm on throttle down + yaw
|
||||||
|
if (activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE))
|
||||||
|
mwDisarm();
|
||||||
|
// Disarm on roll (only when retarded_arm is enabled)
|
||||||
|
if (retarded_arm && activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_LO))
|
||||||
|
mwDisarm();
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// actions during not armed
|
||||||
|
i = 0;
|
||||||
|
|
||||||
|
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
||||||
|
// GYRO calibration
|
||||||
|
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
|
||||||
|
if (feature(FEATURE_GPS))
|
||||||
|
GPS_reset_home_position();
|
||||||
|
#ifdef BARO
|
||||||
|
if (sensors(SENSOR_BARO))
|
||||||
|
baroSetCalibrationCycles(10); // calibrate baro to new ground level (10 * 25 ms = ~250 ms non blocking)
|
||||||
|
#endif
|
||||||
|
if (!sensors(SENSOR_MAG))
|
||||||
|
heading = 0; // reset heading to zero after gyro calibration
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (feature(FEATURE_INFLIGHT_ACC_CAL) && (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_HI)) {
|
||||||
|
// Inflight ACC Calibration
|
||||||
|
handleInflightCalibrationStickPosition();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Multiple configuration profiles
|
||||||
|
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_LO) // ROLL left -> Profile 1
|
||||||
|
i = 1;
|
||||||
|
else if (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_CE) // PITCH up -> Profile 2
|
||||||
|
i = 2;
|
||||||
|
else if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_HI) // ROLL right -> Profile 3
|
||||||
|
i = 3;
|
||||||
|
if (i) {
|
||||||
|
changeProfile(i - 1);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_HI + PIT_CE + ROL_CE)) {
|
||||||
|
// Arm via YAW
|
||||||
|
mwArm();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (retarded_arm && activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_HI)) {
|
||||||
|
// Arm via ROLL
|
||||||
|
mwArm();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rcSticks == THR_HI + YAW_LO + PIT_LO + ROL_CE) {
|
||||||
|
// Calibrating Acc
|
||||||
|
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (rcSticks == THR_HI + YAW_HI + PIT_LO + ROL_CE) {
|
||||||
|
// Calibrating Mag
|
||||||
|
f.CALIBRATE_MAG = 1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Accelerometer Trim
|
||||||
|
|
||||||
|
rollAndPitchTrims_t accelerometerTrimsDelta;
|
||||||
|
memset(&accelerometerTrimsDelta, 0, sizeof(accelerometerTrimsDelta));
|
||||||
|
|
||||||
|
bool shouldApplyRollAndPitchTrimDelta = false;
|
||||||
|
if (rcSticks == THR_HI + YAW_CE + PIT_HI + ROL_CE) {
|
||||||
|
accelerometerTrimsDelta.values.pitch = 2;
|
||||||
|
shouldApplyRollAndPitchTrimDelta = true;
|
||||||
|
} else if (rcSticks == THR_HI + YAW_CE + PIT_LO + ROL_CE) {
|
||||||
|
accelerometerTrimsDelta.values.pitch = -2;
|
||||||
|
shouldApplyRollAndPitchTrimDelta = true;
|
||||||
|
} else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_HI) {
|
||||||
|
accelerometerTrimsDelta.values.roll = 2;
|
||||||
|
shouldApplyRollAndPitchTrimDelta = true;
|
||||||
|
} else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_LO) {
|
||||||
|
accelerometerTrimsDelta.values.roll = -2;
|
||||||
|
shouldApplyRollAndPitchTrimDelta = true;
|
||||||
|
}
|
||||||
|
if (shouldApplyRollAndPitchTrimDelta) {
|
||||||
|
applyAndSaveAccelerometerTrimsDelta(&accelerometerTrimsDelta);
|
||||||
|
rcDelayCommand = 0; // allow autorepetition
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -11,6 +11,11 @@ typedef enum rc_alias {
|
||||||
AUX4
|
AUX4
|
||||||
} rc_alias_e;
|
} rc_alias_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
THROTTLE_LOW = 0,
|
||||||
|
THROTTLE_HIGH
|
||||||
|
} throttleStatus_e;
|
||||||
|
|
||||||
#define ROL_LO (1 << (2 * ROLL))
|
#define ROL_LO (1 << (2 * ROLL))
|
||||||
#define ROL_CE (3 << (2 * ROLL))
|
#define ROL_CE (3 << (2 * ROLL))
|
||||||
#define ROL_HI (2 << (2 * ROLL))
|
#define ROL_HI (2 << (2 * ROLL))
|
||||||
|
@ -36,4 +41,7 @@ typedef struct controlRateConfig_s {
|
||||||
extern int16_t rcCommand[4];
|
extern int16_t rcCommand[4];
|
||||||
|
|
||||||
bool areSticksInApModePosition(uint16_t ap_mode);
|
bool areSticksInApModePosition(uint16_t ap_mode);
|
||||||
|
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
|
||||||
|
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, uint16_t *activate, bool retarded_arm);
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,7 @@
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
|
|
||||||
|
|
|
@ -15,22 +15,22 @@
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
#include "io/serial.h"
|
|
||||||
#include "flight/flight.h"
|
#include "flight/flight.h"
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "io/escservo.h"
|
#include "flight/failsafe.h"
|
||||||
#include "io/rc_controls.h"
|
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "telemetry/telemetry.h"
|
|
||||||
#include "io/gps.h"
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "sensors/battery.h"
|
#include "io/escservo.h"
|
||||||
|
#include "io/gps.h"
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
|
#include "io/rc_controls.h"
|
||||||
|
#include "io/serial.h"
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
#include "flight/failsafe.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
|
@ -15,24 +15,24 @@
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
|
|
||||||
#include "io/serial.h"
|
|
||||||
#include "flight/flight.h"
|
#include "flight/flight.h"
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "io/escservo.h"
|
#include "flight/failsafe.h"
|
||||||
#include "io/rc_controls.h"
|
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "io/gps.h"
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
|
#include "io/escservo.h"
|
||||||
|
#include "io/rc_controls.h"
|
||||||
|
#include "io/gps.h"
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
|
#include "io/serial.h"
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/barometer.h"
|
#include "sensors/barometer.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "flight/failsafe.h"
|
|
||||||
|
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
|
@ -24,10 +24,10 @@
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "rx/rx.h"
|
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/sonar.h"
|
#include "sensors/sonar.h"
|
||||||
|
|
192
src/main/mw.c
192
src/main/mw.c
|
@ -35,9 +35,9 @@
|
||||||
#include "io/serial_cli.h"
|
#include "io/serial_cli.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/statusindicator.h"
|
#include "io/statusindicator.h"
|
||||||
|
#include "rx/rx.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "io/rc_curves.h"
|
#include "io/rc_curves.h"
|
||||||
#include "rx/rx.h"
|
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
|
||||||
|
@ -72,12 +72,13 @@ typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig
|
||||||
|
|
||||||
extern pidControllerFuncPtr pid_controller;
|
extern pidControllerFuncPtr pid_controller;
|
||||||
|
|
||||||
// Automatic ACC Offset Calibration
|
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta)
|
||||||
bool AccInflightCalibrationArmed = false;
|
{
|
||||||
bool AccInflightCalibrationMeasurementDone = false;
|
currentProfile.accelerometerTrims.values.roll += rollAndPitchTrimsDelta->values.roll;
|
||||||
bool AccInflightCalibrationSavetoEEProm = false;
|
currentProfile.accelerometerTrims.values.pitch += rollAndPitchTrimsDelta->values.pitch;
|
||||||
bool AccInflightCalibrationActive = false;
|
|
||||||
uint16_t InflightcalibratingA = 0;
|
saveAndReloadCurrentProfileToCurrentProfileSlot();
|
||||||
|
}
|
||||||
|
|
||||||
void updateAutotuneState(void)
|
void updateAutotuneState(void)
|
||||||
{
|
{
|
||||||
|
@ -247,7 +248,7 @@ void annexCode(void)
|
||||||
static uint32_t LEDTime;
|
static uint32_t LEDTime;
|
||||||
if ((int32_t)(currentTime - LEDTime) >= 0) {
|
if ((int32_t)(currentTime - LEDTime) >= 0) {
|
||||||
LEDTime = currentTime + 50000;
|
LEDTime = currentTime + 50000;
|
||||||
ledringState(f.ARMED, inclination.values.pitchDeciDegrees, inclination.values.rollDeciDegrees);
|
ledringState(f.ARMED, inclination.values.pitchDeciDegrees, inclination.values.rollDeciDegrees, heading);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -262,9 +263,6 @@ void annexCode(void)
|
||||||
// Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities.
|
// Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities.
|
||||||
if (gyro.temperature)
|
if (gyro.temperature)
|
||||||
gyro.temperature(&telemTemperature1);
|
gyro.temperature(&telemTemperature1);
|
||||||
else {
|
|
||||||
// TODO MCU temp
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void mwDisarm(void)
|
void mwDisarm(void)
|
||||||
|
@ -291,18 +289,53 @@ void mwArm(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Automatic ACC Offset Calibration
|
||||||
|
bool AccInflightCalibrationArmed = false;
|
||||||
|
bool AccInflightCalibrationMeasurementDone = false;
|
||||||
|
bool AccInflightCalibrationSavetoEEProm = false;
|
||||||
|
bool AccInflightCalibrationActive = false;
|
||||||
|
uint16_t InflightcalibratingA = 0;
|
||||||
|
|
||||||
|
void handleInflightCalibrationStickPosition(void)
|
||||||
|
{
|
||||||
|
if (AccInflightCalibrationMeasurementDone) {
|
||||||
|
// trigger saving into eeprom after landing
|
||||||
|
AccInflightCalibrationMeasurementDone = false;
|
||||||
|
AccInflightCalibrationSavetoEEProm = true;
|
||||||
|
} else {
|
||||||
|
AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
|
||||||
|
if (AccInflightCalibrationArmed) {
|
||||||
|
queueConfirmationBeep(2);
|
||||||
|
} else {
|
||||||
|
queueConfirmationBeep(3);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateInflightCalibrationState(void)
|
||||||
|
{
|
||||||
|
if (AccInflightCalibrationArmed && f.ARMED && rcData[THROTTLE] > masterConfig.rxConfig.mincheck && !rcOptions[BOXARM]) { // Copter is airborne and you are turning it off via boxarm : start measurement
|
||||||
|
InflightcalibratingA = 50;
|
||||||
|
AccInflightCalibrationArmed = false;
|
||||||
|
}
|
||||||
|
if (rcOptions[BOXCALIB]) { // Use the Calib Option to activate : Calib = TRUE Meausrement started, Land and Calib = 0 measurement stored
|
||||||
|
if (!AccInflightCalibrationActive && !AccInflightCalibrationMeasurementDone)
|
||||||
|
InflightcalibratingA = 50;
|
||||||
|
AccInflightCalibrationActive = true;
|
||||||
|
} else if (AccInflightCalibrationMeasurementDone && !f.ARMED) {
|
||||||
|
AccInflightCalibrationMeasurementDone = false;
|
||||||
|
AccInflightCalibrationSavetoEEProm = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void loop(void)
|
void loop(void)
|
||||||
{
|
{
|
||||||
static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors
|
|
||||||
static uint8_t rcSticks; // this hold sticks position for command combos
|
|
||||||
uint8_t stTmp = 0;
|
|
||||||
int i;
|
int i;
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
static int16_t initialThrottleHold;
|
static int16_t initialThrottleHold;
|
||||||
#endif
|
#endif
|
||||||
static uint32_t loopTime;
|
static uint32_t loopTime;
|
||||||
uint16_t auxState = 0;
|
uint16_t auxState = 0;
|
||||||
bool isThrottleLow = false;
|
|
||||||
|
|
||||||
updateRx();
|
updateRx();
|
||||||
|
|
||||||
|
@ -326,138 +359,17 @@ void loop(void)
|
||||||
failsafe->vTable->updateState();
|
failsafe->vTable->updateState();
|
||||||
}
|
}
|
||||||
|
|
||||||
// ------------------ STICKS COMMAND HANDLER --------------------
|
throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
||||||
// checking sticks positions
|
|
||||||
for (i = 0; i < 4; i++) {
|
|
||||||
stTmp >>= 2;
|
|
||||||
if (rcData[i] > masterConfig.rxConfig.mincheck)
|
|
||||||
stTmp |= 0x80; // check for MIN
|
|
||||||
if (rcData[i] < masterConfig.rxConfig.maxcheck)
|
|
||||||
stTmp |= 0x40; // check for MAX
|
|
||||||
}
|
|
||||||
if (stTmp == rcSticks) {
|
|
||||||
if (rcDelayCommand < 250)
|
|
||||||
rcDelayCommand++;
|
|
||||||
} else
|
|
||||||
rcDelayCommand = 0;
|
|
||||||
rcSticks = stTmp;
|
|
||||||
|
|
||||||
// perform actions
|
if (throttleStatus == THROTTLE_LOW) {
|
||||||
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (masterConfig.rxConfig.midrc - masterConfig.flight3DConfig.deadband3d_throttle) && rcData[THROTTLE] < (masterConfig.rxConfig.midrc + masterConfig.flight3DConfig.deadband3d_throttle)))
|
|
||||||
isThrottleLow = true;
|
|
||||||
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < masterConfig.rxConfig.mincheck))
|
|
||||||
isThrottleLow = true;
|
|
||||||
if (isThrottleLow) {
|
|
||||||
resetErrorAngle();
|
resetErrorAngle();
|
||||||
resetErrorGyro();
|
resetErrorGyro();
|
||||||
if (currentProfile.activate[BOXARM] > 0) { // Arming/Disarming via ARM BOX
|
|
||||||
if (rcOptions[BOXARM] && f.OK_TO_ARM)
|
|
||||||
mwArm();
|
|
||||||
else if (f.ARMED)
|
|
||||||
mwDisarm();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rcDelayCommand == 20) {
|
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, currentProfile.activate, masterConfig.retarded_arm);
|
||||||
if (f.ARMED) { // actions during armed
|
|
||||||
// Disarm on throttle down + yaw
|
|
||||||
if (currentProfile.activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE))
|
|
||||||
mwDisarm();
|
|
||||||
// Disarm on roll (only when retarded_arm is enabled)
|
|
||||||
if (masterConfig.retarded_arm && currentProfile.activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_LO))
|
|
||||||
mwDisarm();
|
|
||||||
} else { // actions during not armed
|
|
||||||
i = 0;
|
|
||||||
// GYRO calibration
|
|
||||||
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
|
||||||
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
|
|
||||||
if (feature(FEATURE_GPS))
|
|
||||||
GPS_reset_home_position();
|
|
||||||
#ifdef BARO
|
|
||||||
if (sensors(SENSOR_BARO))
|
|
||||||
baroSetCalibrationCycles(10); // calibrate baro to new ground level (10 * 25 ms = ~250 ms non blocking)
|
|
||||||
#endif
|
|
||||||
if (!sensors(SENSOR_MAG))
|
|
||||||
heading = 0; // reset heading to zero after gyro calibration
|
|
||||||
// Inflight ACC Calibration
|
|
||||||
} else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_HI)) {
|
|
||||||
if (AccInflightCalibrationMeasurementDone) { // trigger saving into eeprom after landing
|
|
||||||
AccInflightCalibrationMeasurementDone = false;
|
|
||||||
AccInflightCalibrationSavetoEEProm = true;
|
|
||||||
} else {
|
|
||||||
AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
|
|
||||||
if (AccInflightCalibrationArmed) {
|
|
||||||
queueConfirmationBeep(2);
|
|
||||||
} else {
|
|
||||||
queueConfirmationBeep(3);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Multiple configuration profiles
|
|
||||||
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_LO) // ROLL left -> Profile 1
|
|
||||||
i = 1;
|
|
||||||
else if (rcSticks == THR_LO + YAW_LO + PIT_HI + ROL_CE) // PITCH up -> Profile 2
|
|
||||||
i = 2;
|
|
||||||
else if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_HI) // ROLL right -> Profile 3
|
|
||||||
i = 3;
|
|
||||||
if (i) {
|
|
||||||
masterConfig.current_profile_index = i - 1;
|
|
||||||
writeEEPROM();
|
|
||||||
readEEPROM();
|
|
||||||
blinkLedAndSoundBeeper(2, 40, i);
|
|
||||||
// TODO alarmArray[0] = i;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Arm via YAW
|
|
||||||
if (currentProfile.activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_HI + PIT_CE + ROL_CE))
|
|
||||||
mwArm();
|
|
||||||
// Arm via ROLL
|
|
||||||
else if (masterConfig.retarded_arm && currentProfile.activate[BOXARM] == 0 && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_HI))
|
|
||||||
mwArm();
|
|
||||||
// Calibrating Acc
|
|
||||||
else if (rcSticks == THR_HI + YAW_LO + PIT_LO + ROL_CE)
|
|
||||||
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
|
||||||
// Calibrating Mag
|
|
||||||
else if (rcSticks == THR_HI + YAW_HI + PIT_LO + ROL_CE)
|
|
||||||
f.CALIBRATE_MAG = 1;
|
|
||||||
i = 0;
|
|
||||||
// Acc Trim
|
|
||||||
if (rcSticks == THR_HI + YAW_CE + PIT_HI + ROL_CE) {
|
|
||||||
currentProfile.accelerometerTrims.values.pitch += 2;
|
|
||||||
i = 1;
|
|
||||||
} else if (rcSticks == THR_HI + YAW_CE + PIT_LO + ROL_CE) {
|
|
||||||
currentProfile.accelerometerTrims.values.pitch -= 2;
|
|
||||||
i = 1;
|
|
||||||
} else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_HI) {
|
|
||||||
currentProfile.accelerometerTrims.values.roll += 2;
|
|
||||||
i = 1;
|
|
||||||
} else if (rcSticks == THR_HI + YAW_CE + PIT_CE + ROL_LO) {
|
|
||||||
currentProfile.accelerometerTrims.values.roll -= 2;
|
|
||||||
i = 1;
|
|
||||||
}
|
|
||||||
if (i) {
|
|
||||||
copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
|
|
||||||
writeEEPROM();
|
|
||||||
readEEPROMAndNotify();
|
|
||||||
rcDelayCommand = 0; // allow autorepetition
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
|
if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
|
||||||
if (AccInflightCalibrationArmed && f.ARMED && rcData[THROTTLE] > masterConfig.rxConfig.mincheck && !rcOptions[BOXARM]) { // Copter is airborne and you are turning it off via boxarm : start measurement
|
updateInflightCalibrationState();
|
||||||
InflightcalibratingA = 50;
|
|
||||||
AccInflightCalibrationArmed = false;
|
|
||||||
}
|
|
||||||
if (rcOptions[BOXCALIB]) { // Use the Calib Option to activate : Calib = TRUE Meausrement started, Land and Calib = 0 measurement stored
|
|
||||||
if (!AccInflightCalibrationActive && !AccInflightCalibrationMeasurementDone)
|
|
||||||
InflightcalibratingA = 50;
|
|
||||||
AccInflightCalibrationActive = true;
|
|
||||||
} else if (AccInflightCalibrationMeasurementDone && !f.ARMED) {
|
|
||||||
AccInflightCalibrationMeasurementDone = false;
|
|
||||||
AccInflightCalibrationSavetoEEProm = true;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check AUX switches
|
// Check AUX switches
|
||||||
|
|
7
src/main/mw.h
Normal file
7
src/main/mw.h
Normal file
|
@ -0,0 +1,7 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta);
|
||||||
|
void handleInflightCalibrationStickPosition();
|
||||||
|
|
||||||
|
void mwDisarm(void);
|
||||||
|
void mwArm(void);
|
Loading…
Add table
Add a link
Reference in a new issue