mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 16:25:26 +03:00
commit
3ef57a23a1
30 changed files with 5905 additions and 692 deletions
|
@ -81,7 +81,7 @@ IPF can be edited using INAV Configurator user interface, of via CLI
|
|||
| Operand Type | Name | Notes |
|
||||
|---- |---- |---- |
|
||||
| 0 | VALUE | Value derived from `value` field |
|
||||
| 1 | RC_CHANNEL | `value` points to RC channel number, indexed from 1 |
|
||||
| 1 | GET_RC_CHANNEL | `value` points to RC channel number, indexed from 1 |
|
||||
| 2 | FLIGHT | `value` points to flight parameter table |
|
||||
| 3 | FLIGHT_MODE | `value` points to flight modes table |
|
||||
| 4 | LC | `value` points to other logic condition ID |
|
||||
|
|
6194
docs/Settings.md
6194
docs/Settings.md
File diff suppressed because it is too large
Load diff
|
@ -109,7 +109,7 @@
|
|||
|
||||
#define SYM_AH_CH_CENTER 0x7E // 126 Crossair center
|
||||
|
||||
// 0x7F // 127 -
|
||||
#define SYM_GLIDESLOPE 0x7F // 127 Glideslope
|
||||
|
||||
#define SYM_AH_H_START 0x80 // 128 to 136 Horizontal AHI
|
||||
|
||||
|
|
|
@ -223,7 +223,7 @@ static void updateArmingStatus(void)
|
|||
|
||||
/* CHECK: pitch / roll sticks centered when NAV_LAUNCH_MODE enabled */
|
||||
if (isNavLaunchEnabled()) {
|
||||
if (areSticksDeflectedMoreThanPosHoldDeadband()) {
|
||||
if (areSticksDeflected()) {
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED);
|
||||
} else {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED);
|
||||
|
|
|
@ -326,7 +326,7 @@ void initActiveBoxIds(void)
|
|||
#endif
|
||||
}
|
||||
|
||||
#define IS_ENABLED(mask) (mask == 0 ? 0 : 1)
|
||||
#define IS_ENABLED(mask) ((mask) == 0 ? 0 : 1)
|
||||
#define CHECK_ACTIVE_BOX(condition, index) do { if (IS_ENABLED(condition)) { activeBoxes[index] = 1; } } while(0)
|
||||
|
||||
void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags)
|
||||
|
|
|
@ -71,12 +71,13 @@ stickPositions_e rcStickPositions;
|
|||
|
||||
FASTRAM int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 3);
|
||||
|
||||
PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig,
|
||||
.deadband = SETTING_DEADBAND_DEFAULT,
|
||||
.yaw_deadband = SETTING_YAW_DEADBAND_DEFAULT,
|
||||
.pos_hold_deadband = SETTING_POS_HOLD_DEADBAND_DEFAULT,
|
||||
.control_deadband = SETTING_CONTROL_DEADBAND_DEFAULT,
|
||||
.alt_hold_deadband = SETTING_ALT_HOLD_DEADBAND_DEFAULT,
|
||||
.mid_throttle_deadband = SETTING_3D_DEADBAND_THROTTLE_DEFAULT,
|
||||
.airmodeHandlingType = SETTING_AIRMODE_TYPE_DEFAULT,
|
||||
|
@ -97,9 +98,14 @@ bool areSticksInApModePosition(uint16_t ap_mode)
|
|||
return ABS(rcCommand[ROLL]) < ap_mode && ABS(rcCommand[PITCH]) < ap_mode;
|
||||
}
|
||||
|
||||
bool areSticksDeflectedMoreThanPosHoldDeadband(void)
|
||||
bool areSticksDeflected(void)
|
||||
{
|
||||
return (ABS(rcCommand[ROLL]) > rcControlsConfig()->pos_hold_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->pos_hold_deadband);
|
||||
return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[YAW]) > rcControlsConfig()->control_deadband);
|
||||
}
|
||||
|
||||
bool isRollPitchStickDeflected(void)
|
||||
{
|
||||
return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband);
|
||||
}
|
||||
|
||||
throttleStatus_e FAST_CODE NOINLINE calculateThrottleStatus(throttleStatusType_e type)
|
||||
|
|
|
@ -84,7 +84,8 @@ extern int16_t rcCommand[4];
|
|||
typedef struct rcControlsConfig_s {
|
||||
uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.
|
||||
uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero.
|
||||
uint8_t pos_hold_deadband; // Adds ability to adjust the Hold-position when moving the sticks (assisted mode)
|
||||
uint8_t pos_hold_deadband; // Deadband for position hold
|
||||
uint8_t control_deadband; // General deadband to check if sticks are deflected, us PWM.
|
||||
uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold
|
||||
uint16_t mid_throttle_deadband; // default throttle deadband from MIDRC
|
||||
uint8_t airmodeHandlingType; // Defaults to ANTI_WINDUP triggered at sticks centered
|
||||
|
@ -106,7 +107,8 @@ stickPositions_e getRcStickPositions(void);
|
|||
bool checkStickPosition(stickPositions_e stickPos);
|
||||
|
||||
bool areSticksInApModePosition(uint16_t ap_mode);
|
||||
bool areSticksDeflectedMoreThanPosHoldDeadband(void);
|
||||
bool areSticksDeflected(void);
|
||||
bool isRollPitchStickDeflected(void);
|
||||
throttleStatus_e calculateThrottleStatus(throttleStatusType_e type);
|
||||
rollPitchStatus_e calculateRollPitchCenterStatus(void);
|
||||
void processRcStickPositions(throttleStatus_e throttleStatus);
|
||||
|
|
|
@ -182,12 +182,12 @@ tables:
|
|||
|
||||
constants:
|
||||
RPYL_PID_MIN: 0
|
||||
RPYL_PID_MAX: 200
|
||||
RPYL_PID_MAX: 255
|
||||
|
||||
MANUAL_RATE_MIN: 0
|
||||
MANUAL_RATE_MAX: 100
|
||||
|
||||
ROLL_PITCH_RATE_MIN: 6
|
||||
ROLL_PITCH_RATE_MIN: 4
|
||||
ROLL_PITCH_RATE_MAX: 180
|
||||
|
||||
groups:
|
||||
|
@ -214,7 +214,7 @@ groups:
|
|||
description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz"
|
||||
default_value: 250
|
||||
field: gyro_anti_aliasing_lpf_hz
|
||||
max: 255
|
||||
max: 1000
|
||||
- name: gyro_anti_aliasing_lpf_type
|
||||
description: "Specifies the type of the software LPF of the gyro signals."
|
||||
default_value: "PT1"
|
||||
|
@ -1289,7 +1289,7 @@ groups:
|
|||
description: "Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure."
|
||||
default_value: 20
|
||||
field: stabilized.rates[FD_YAW]
|
||||
min: 2
|
||||
min: 1
|
||||
max: 180
|
||||
- name: manual_rc_expo
|
||||
description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
|
||||
|
@ -1505,7 +1505,12 @@ groups:
|
|||
min: 0
|
||||
max: 100
|
||||
- name: pos_hold_deadband
|
||||
description: "Stick deadband in [r/c points], applied after r/c deadband and expo"
|
||||
description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes."
|
||||
default_value: 10
|
||||
min: 2
|
||||
max: 250
|
||||
- name: control_deadband
|
||||
description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered."
|
||||
default_value: 10
|
||||
min: 2
|
||||
max: 250
|
||||
|
@ -2118,12 +2123,6 @@ groups:
|
|||
field: fixedWingLevelTrimGain
|
||||
min: 0
|
||||
max: 20
|
||||
- name: fw_level_pitch_deadband
|
||||
description: "Deadband for automatic leveling when AUTOLEVEL mode is used."
|
||||
default_value: 5
|
||||
field: fixedWingLevelTrimDeadband
|
||||
min: 0
|
||||
max: 20
|
||||
|
||||
- name: PG_PID_AUTOTUNE_CONFIG
|
||||
type: pidAutotuneConfig_t
|
||||
|
@ -2161,7 +2160,7 @@ groups:
|
|||
type: uint8_t
|
||||
- name: fw_autotune_max_rate_deflection
|
||||
description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`."
|
||||
default_value: 80
|
||||
default_value: 90
|
||||
field: fw_max_rate_deflection
|
||||
min: 50
|
||||
max: 100
|
||||
|
@ -2687,6 +2686,12 @@ groups:
|
|||
field: fw.launch_idle_throttle
|
||||
min: 1000
|
||||
max: 2000
|
||||
- name: nav_fw_launch_idle_motor_delay
|
||||
description: "Delay between raising throttle and motor starting at idle throttle (ms)"
|
||||
default_value: 0
|
||||
field: fw.launch_idle_motor_timer
|
||||
min: 0
|
||||
max: 60000
|
||||
- name: nav_fw_launch_motor_delay
|
||||
description: "Delay between detected launch and launch sequence start and throttling up (ms)"
|
||||
default_value: 500
|
||||
|
@ -3126,6 +3131,13 @@ groups:
|
|||
field: link_quality_alarm
|
||||
min: 0
|
||||
max: 100
|
||||
- name: osd_rssi_dbm_alarm
|
||||
condition: USE_SERIALRX_CRSF
|
||||
description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm"
|
||||
default_value: 0
|
||||
field: rssi_dbm_alarm
|
||||
min: -130
|
||||
max: 0
|
||||
- name: osd_temp_label_align
|
||||
description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
|
||||
default_value: "LEFT"
|
||||
|
@ -3164,11 +3176,16 @@ groups:
|
|||
min: -2
|
||||
max: 2
|
||||
- name: osd_camera_uptilt
|
||||
description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal"
|
||||
description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal. Used for correct display of HUD items and AHI (when enabled)."
|
||||
default_value: 0
|
||||
field: camera_uptilt
|
||||
min: -40
|
||||
max: 80
|
||||
- name: osd_ahi_camera_uptilt_comp
|
||||
description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. When set to `OFF`, the AHI will appear in the center of the OSD regardless of camera angle, but can still be shifted up and down using `osd_horizon_offset` (`osd_ahi_vertical_offset` for pixel-OSD)."
|
||||
default_value: OFF
|
||||
field: ahi_camera_uptilt_comp
|
||||
type: bool
|
||||
- name: osd_camera_fov_h
|
||||
description: "Horizontal field of view for the camera in degres"
|
||||
default_value: 135
|
||||
|
|
|
@ -504,7 +504,7 @@ static float imuCalculateAccelerometerWeight(const float dT)
|
|||
float accWeight_RateIgnore = 1.0f;
|
||||
|
||||
if (ARMING_FLAG(ARMED) && STATE(FIXED_WING_LEGACY) && imuConfig()->acc_ignore_rate) {
|
||||
const float rotRateMagnitude = sqrtf(vectorNormSquared(&imuMeasuredRotationBF));
|
||||
const float rotRateMagnitude = sqrtf(sq(imuMeasuredRotationBF.y) + sq(imuMeasuredRotationBF.z));
|
||||
const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, IMU_CENTRIFUGAL_LPF, dT);
|
||||
|
||||
if (imuConfig()->acc_ignore_slope) {
|
||||
|
|
|
@ -308,7 +308,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
|
||||
.fixedWingLevelTrim = SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT,
|
||||
.fixedWingLevelTrimGain = SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT,
|
||||
.fixedWingLevelTrimDeadband = SETTING_FW_LEVEL_PITCH_DEADBAND_DEFAULT,
|
||||
|
||||
#ifdef USE_SMITH_PREDICTOR
|
||||
.smithPredictorStrength = SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT,
|
||||
|
@ -616,21 +615,6 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h
|
|||
DEBUG_SET(DEBUG_AUTOLEVEL, 1, fixedWingLevelTrim * 10);
|
||||
DEBUG_SET(DEBUG_AUTOLEVEL, 2, getEstimatedActualVelocity(Z));
|
||||
|
||||
/*
|
||||
* fixedWingLevelTrim has opposite sign to rcCommand.
|
||||
* Positive rcCommand means nose should point downwards
|
||||
* Negative rcCommand mean nose should point upwards
|
||||
* This is counter intuitive and a natural way suggests that + should mean UP
|
||||
* This is why fixedWingLevelTrim has opposite sign to rcCommand
|
||||
* Positive fixedWingLevelTrim means nose should point upwards
|
||||
* Negative fixedWingLevelTrim means nose should point downwards
|
||||
*/
|
||||
angleTarget -= fixedWingLevelTrim;
|
||||
DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10);
|
||||
}
|
||||
|
||||
//PITCH trim applied by a AutoLevel flight mode and manual pitch trimming
|
||||
if (axis == FD_PITCH && STATE(AIRPLANE)) {
|
||||
/*
|
||||
* fixedWingLevelTrim has opposite sign to rcCommand.
|
||||
* Positive rcCommand means nose should point downwards
|
||||
|
@ -641,6 +625,7 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h
|
|||
* Negative fixedWingLevelTrim means nose should point downwards
|
||||
*/
|
||||
angleTarget -= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim);
|
||||
DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10);
|
||||
}
|
||||
|
||||
#ifdef USE_SECONDARY_IMU
|
||||
|
@ -795,7 +780,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh
|
|||
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit);
|
||||
}
|
||||
|
||||
axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidState->pidSumLimit, +pidState->pidSumLimit);
|
||||
axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit);
|
||||
|
||||
#ifdef USE_AUTOTUNE_FIXED_WING
|
||||
if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) {
|
||||
|
@ -1327,11 +1312,10 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs)
|
|||
*/
|
||||
pidControllerFlags_e flags = PID_LIMIT_INTEGRATOR;
|
||||
|
||||
//Iterm should freeze when pitch stick is deflected
|
||||
//Iterm should freeze when sticks are deflected
|
||||
if (
|
||||
!IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) ||
|
||||
rxGetChannelValue(PITCH) > (PWM_RANGE_MIDDLE + pidProfile()->fixedWingLevelTrimDeadband) ||
|
||||
rxGetChannelValue(PITCH) < (PWM_RANGE_MIDDLE - pidProfile()->fixedWingLevelTrimDeadband) ||
|
||||
areSticksDeflected() ||
|
||||
(!FLIGHT_MODE(ANGLE_MODE) && !FLIGHT_MODE(HORIZON_MODE)) ||
|
||||
navigationIsControllingAltitude()
|
||||
) {
|
||||
|
@ -1355,3 +1339,8 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs)
|
|||
|
||||
previousArmingState = !!ARMING_FLAG(ARMED);
|
||||
}
|
||||
|
||||
float getFixedWingLevelTrim(void)
|
||||
{
|
||||
return STATE(AIRPLANE) ? fixedWingLevelTrim : 0;
|
||||
}
|
||||
|
|
|
@ -165,7 +165,6 @@ typedef struct pidProfile_s {
|
|||
|
||||
float fixedWingLevelTrim;
|
||||
float fixedWingLevelTrimGain;
|
||||
float fixedWingLevelTrimDeadband;
|
||||
#ifdef USE_SMITH_PREDICTOR
|
||||
float smithPredictorStrength;
|
||||
float smithPredictorDelay;
|
||||
|
@ -233,3 +232,4 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa
|
|||
pidType_e pidIndexGetType(pidIndex_e pidIndex);
|
||||
|
||||
void updateFixedWingLevelTrim(timeUs_t currentTimeUs);
|
||||
float getFixedWingLevelTrim(void);
|
||||
|
|
|
@ -47,14 +47,14 @@
|
|||
#include "flight/pid.h"
|
||||
|
||||
#define AUTOTUNE_FIXED_WING_MIN_FF 10
|
||||
#define AUTOTUNE_FIXED_WING_MAX_FF 200
|
||||
#define AUTOTUNE_FIXED_WING_MAX_FF 255
|
||||
#define AUTOTUNE_FIXED_WING_MIN_ROLL_PITCH_RATE 40
|
||||
#define AUTOTUNE_FIXED_WING_MIN_YAW_RATE 10
|
||||
#define AUTOTUNE_FIXED_WING_MAX_RATE 720
|
||||
#define AUTOTUNE_FIXED_WING_CONVERGENCE_RATE 10
|
||||
#define AUTOTUNE_FIXED_WING_SAMPLE_INTERVAL 20 // ms
|
||||
#define AUTOTUNE_FIXED_WING_SAMPLES 1000 // Use averagea over the last 20 seconds
|
||||
#define AUTOTUNE_FIXED_WING_MIN_SAMPLES 250 // Start updating tune after 5 seconds
|
||||
#define AUTOTUNE_FIXED_WING_SAMPLES 1000 // Use average over the last 20 seconds of hard maneuvers
|
||||
#define AUTOTUNE_FIXED_WING_MIN_SAMPLES 250 // Start updating tune after 5 seconds of hard maneuvers
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(pidAutotuneConfig_t, pidAutotuneConfig, PG_PID_AUTOTUNE_CONFIG, 2);
|
||||
|
||||
|
|
|
@ -192,7 +192,6 @@ void powerLimiterApply(int16_t *throttleCommand) {
|
|||
currentThrottleCommand = currentThrAttned;
|
||||
} else {
|
||||
wasLimitingCurrent = false;
|
||||
currentThrAttnIntegrator = 0;
|
||||
pt1FilterReset(¤tThrAttnFilter, 0);
|
||||
|
||||
currentThrottleCommand = *throttleCommand;
|
||||
|
@ -222,7 +221,6 @@ void powerLimiterApply(int16_t *throttleCommand) {
|
|||
powerThrottleCommand = powerThrAttned;
|
||||
} else {
|
||||
wasLimitingPower = false;
|
||||
powerThrAttnIntegrator = 0;
|
||||
pt1FilterReset(&powerThrAttnFilter, 0);
|
||||
|
||||
powerThrottleCommand = *throttleCommand;
|
||||
|
|
|
@ -490,6 +490,7 @@ void processServoAutotrimMode(void)
|
|||
#define SERVO_AUTOTRIM_CENTER_MIN 1300
|
||||
#define SERVO_AUTOTRIM_CENTER_MAX 1700
|
||||
#define SERVO_AUTOTRIM_UPDATE_SIZE 5
|
||||
#define SERVO_AUTOTRIM_ATIITUDE_LIMIT 50 // 5 degrees
|
||||
|
||||
void processContinuousServoAutotrim(const float dT)
|
||||
{
|
||||
|
@ -497,21 +498,22 @@ void processContinuousServoAutotrim(const float dT)
|
|||
static servoAutotrimState_e trimState = AUTOTRIM_IDLE;
|
||||
static uint32_t servoMiddleUpdateCount;
|
||||
|
||||
const float rotRateMagnitude = sqrtf(vectorNormSquared(&imuMeasuredRotationBF));
|
||||
const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
|
||||
const float targetRateMagnitude = getTotalRateTarget();
|
||||
const float targetRateMagnitudeFiltered = pt1FilterApply4(&targetRateFilter, targetRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
|
||||
const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, sqrtf(vectorNormSquared(&imuMeasuredRotationBF)), SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
|
||||
const float targetRateMagnitudeFiltered = pt1FilterApply4(&targetRateFilter, getTotalRateTarget(), SERVO_AUTOTRIM_FILTER_CUTOFF, dT);
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
trimState = AUTOTRIM_COLLECTING;
|
||||
if ((millis() - lastUpdateTimeMs) > 500) {
|
||||
const bool planeIsFlyingStraight = rotRateMagnitudeFiltered <= DEGREES_TO_RADIANS(servoConfig()->servo_autotrim_rotation_limit);
|
||||
const bool noRotationCommanded = targetRateMagnitudeFiltered <= servoConfig()->servo_autotrim_rotation_limit;
|
||||
const bool planeIsFlyingLevel = calculateCosTiltAngle() >= 0.878153032f;
|
||||
const bool sticksAreCentered = !areSticksDeflected();
|
||||
const bool planeIsFlyingLevel = ABS(attitude.values.pitch + DEGREES_TO_DECIDEGREES(getFixedWingLevelTrim())) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT
|
||||
&& ABS(attitude.values.roll) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT;
|
||||
if (
|
||||
planeIsFlyingStraight &&
|
||||
noRotationCommanded &&
|
||||
planeIsFlyingLevel &&
|
||||
sticksAreCentered &&
|
||||
!FLIGHT_MODE(MANUAL_MODE) &&
|
||||
isGPSHeadingValid() // TODO: proper flying detection
|
||||
) {
|
||||
|
|
|
@ -132,6 +132,10 @@ static const uint8_t beep_launchModeBeep[] = {
|
|||
static const uint8_t beep_launchModeLowThrottleBeep[] = {
|
||||
5, 5, 5, 5, 3, 100, BEEPER_COMMAND_STOP
|
||||
};
|
||||
// 4 short beeps and a pause. Warning motor about to start at idle throttle
|
||||
static const uint8_t beep_launchModeIdleStartBeep[] = {
|
||||
5, 5, 5, 5, 5, 5, 5, 80, BEEPER_COMMAND_STOP
|
||||
};
|
||||
// short beeps
|
||||
static const uint8_t beep_hardwareFailure[] = {
|
||||
10, 10, BEEPER_COMMAND_STOP
|
||||
|
@ -196,11 +200,12 @@ typedef struct beeperTableEntry_s {
|
|||
{ BEEPER_ENTRY(BEEPER_USB, 18, NULL, "ON_USB") },
|
||||
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_ENABLED, 19, beep_launchModeBeep, "LAUNCH_MODE") },
|
||||
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_LOW_THROTTLE, 20, beep_launchModeLowThrottleBeep, "LAUNCH_MODE_LOW_THROTTLE") },
|
||||
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 21, beep_camOpenBeep, "CAM_CONNECTION_OPEN") },
|
||||
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 22, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") },
|
||||
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_IDLE_START, 21, beep_launchModeIdleStartBeep, "LAUNCH_MODE_IDLE_START") },
|
||||
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 22, beep_camOpenBeep, "CAM_CONNECTION_OPEN") },
|
||||
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 23, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") },
|
||||
|
||||
{ BEEPER_ENTRY(BEEPER_ALL, 23, NULL, "ALL") },
|
||||
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 24, NULL, "PREFERED") },
|
||||
{ BEEPER_ENTRY(BEEPER_ALL, 24, NULL, "ALL") },
|
||||
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 25, NULL, "PREFERED") },
|
||||
};
|
||||
|
||||
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
||||
|
|
|
@ -44,6 +44,7 @@ typedef enum {
|
|||
BEEPER_USB, // Some boards have beeper powered USB connected
|
||||
BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled
|
||||
BEEPER_LAUNCH_MODE_LOW_THROTTLE, // Fixed-wing launch mode enabled, but throttle is low
|
||||
BEEPER_LAUNCH_MODE_IDLE_START, // Fixed-wing launch mode enabled, motor about to start at idle after set delay
|
||||
BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated
|
||||
BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop
|
||||
|
||||
|
|
|
@ -194,7 +194,7 @@ static bool osdDisplayHasCanvas;
|
|||
|
||||
#define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees)
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 4);
|
||||
PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0);
|
||||
|
||||
static int digitCount(int32_t value)
|
||||
|
@ -1383,6 +1383,25 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY,
|
|||
displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr);
|
||||
}
|
||||
|
||||
int8_t getGeoWaypointNumber(int8_t waypointIndex)
|
||||
{
|
||||
static int8_t lastWaypointIndex = 1;
|
||||
static int8_t geoWaypointIndex;
|
||||
|
||||
if (waypointIndex != lastWaypointIndex) {
|
||||
lastWaypointIndex = geoWaypointIndex = waypointIndex;
|
||||
for (uint8_t i = 0; i <= waypointIndex; i++) {
|
||||
if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI ||
|
||||
posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD ||
|
||||
posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) {
|
||||
geoWaypointIndex -= 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return geoWaypointIndex + 1;
|
||||
}
|
||||
|
||||
static bool osdDrawSingleElement(uint8_t item)
|
||||
{
|
||||
uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item];
|
||||
|
@ -1495,6 +1514,27 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
break;
|
||||
}
|
||||
|
||||
case OSD_GLIDESLOPE:
|
||||
{
|
||||
float horizontalSpeed = gpsSol.groundSpeed;
|
||||
float sinkRate = -getEstimatedActualVelocity(Z);
|
||||
static pt1Filter_t gsFilterState;
|
||||
const timeMs_t currentTimeMs = millis();
|
||||
static timeMs_t gsUpdatedTimeMs;
|
||||
float glideSlope = horizontalSpeed / sinkRate;
|
||||
glideSlope = pt1FilterApply4(&gsFilterState, isnormal(glideSlope) ? glideSlope : 200, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs));
|
||||
gsUpdatedTimeMs = currentTimeMs;
|
||||
|
||||
buff[0] = SYM_GLIDESLOPE;
|
||||
if (glideSlope > 0.0f && glideSlope < 100.0f) {
|
||||
osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3);
|
||||
} else {
|
||||
buff[1] = buff[2] = buff[3] = '-';
|
||||
}
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_GPS_LAT:
|
||||
osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat);
|
||||
break;
|
||||
|
@ -1858,6 +1898,8 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
}
|
||||
if (!failsafeIsReceivingRxData()){
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
} else if (osdConfig()->rssi_dbm_alarm && rssi < osdConfig()->rssi_dbm_alarm) {
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -1893,7 +1935,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
snrUpdated = millis();
|
||||
|
||||
const char* showsnr = "-20";
|
||||
const char* hidesnr = " ";
|
||||
const char* hidesnr = " ";
|
||||
if (snrFiltered > osdConfig()->snr_alarm) {
|
||||
if (cmsInMenu) {
|
||||
buff[0] = SYM_SNR;
|
||||
|
@ -1984,8 +2026,9 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
fpVector3_t poi;
|
||||
geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &wp2, waypointMissionAltConvMode(posControl.waypointList[j].p3));
|
||||
int32_t altConvModeAltitude = waypointMissionAltConvMode(posControl.waypointList[j].p3) == GEO_ALT_ABSOLUTE ? osdGetAltitudeMsl() : osdGetAltitude();
|
||||
while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more
|
||||
osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 49 + j, i);
|
||||
j = getGeoWaypointNumber(j);
|
||||
while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more (48 = ascii 0)
|
||||
osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 48 + j, i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2028,7 +2071,8 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll);
|
||||
pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch);
|
||||
#endif
|
||||
pitchAngle -= DEGREES_TO_RADIANS(osdConfig()->camera_uptilt);
|
||||
pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0;
|
||||
pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim());
|
||||
if (osdConfig()->ahi_reverse_roll) {
|
||||
rollAngle = -rollAngle;
|
||||
}
|
||||
|
@ -2881,6 +2925,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
|
|||
.snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT,
|
||||
.crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT,
|
||||
.link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT,
|
||||
.rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT,
|
||||
#endif
|
||||
#ifdef USE_TEMPERATURE_SENSOR
|
||||
.temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT,
|
||||
|
@ -2894,6 +2939,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
|
|||
.crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT,
|
||||
.horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT,
|
||||
.camera_uptilt = SETTING_OSD_CAMERA_UPTILT_DEFAULT,
|
||||
.ahi_camera_uptilt_comp = SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT,
|
||||
.camera_fov_h = SETTING_OSD_CAMERA_FOV_H_DEFAULT,
|
||||
.camera_fov_v = SETTING_OSD_CAMERA_FOV_V_DEFAULT,
|
||||
.hud_margin_h = SETTING_OSD_HUD_MARGIN_H_DEFAULT,
|
||||
|
@ -2956,6 +3002,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
|
|||
osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1);
|
||||
osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1);
|
||||
osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1);
|
||||
osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2);
|
||||
|
||||
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG;
|
||||
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2);
|
||||
|
@ -2981,17 +3028,17 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
|
|||
// OSD_VARIO_NUM at the right of OSD_VARIO
|
||||
osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7);
|
||||
osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11);
|
||||
osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
|
||||
osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
|
||||
osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6);
|
||||
osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6);
|
||||
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2);
|
||||
osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6);
|
||||
|
||||
#ifdef USE_SERIALRX_CRSF
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(24, 12);
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(24, 11);
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(25, 9);
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(25, 10);
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12);
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(23, 11);
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(24, 9);
|
||||
osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10);
|
||||
#endif
|
||||
|
||||
osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8);
|
||||
|
@ -3828,7 +3875,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
|
|||
// Countdown display for remaining Waypoints
|
||||
char buf[6];
|
||||
osdFormatDistanceSymbol(buf, posControl.wpDistance, 0);
|
||||
tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", posControl.activeWaypointIndex + 1, posControl.waypointCount, buf);
|
||||
tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf);
|
||||
messages[messageCount++] = messageBuf;
|
||||
} else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) {
|
||||
// WP hold time countdown in seconds
|
||||
|
@ -3864,7 +3911,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
|
|||
// by OSD_FLYMODE.
|
||||
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD);
|
||||
}
|
||||
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) {
|
||||
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM);
|
||||
}
|
||||
if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) {
|
||||
|
|
|
@ -231,6 +231,7 @@ typedef enum {
|
|||
OSD_PLIMIT_REMAINING_BURST_TIME,
|
||||
OSD_PLIMIT_ACTIVE_CURRENT_LIMIT,
|
||||
OSD_PLIMIT_ACTIVE_POWER_LIMIT,
|
||||
OSD_GLIDESLOPE,
|
||||
OSD_ITEM_COUNT // MUST BE LAST
|
||||
} osd_items_e;
|
||||
|
||||
|
@ -312,6 +313,7 @@ typedef struct osdConfig_s {
|
|||
#ifdef USE_SERIALRX_CRSF
|
||||
int8_t snr_alarm; //CRSF SNR alarm in dB
|
||||
int8_t link_quality_alarm;
|
||||
int16_t rssi_dbm_alarm; // in dBm
|
||||
#endif
|
||||
#ifdef USE_BARO
|
||||
int16_t baro_temp_alarm_min;
|
||||
|
@ -331,6 +333,7 @@ typedef struct osdConfig_s {
|
|||
uint8_t crosshairs_style; // from osd_crosshairs_style_e
|
||||
int8_t horizon_offset;
|
||||
int8_t camera_uptilt;
|
||||
bool ahi_camera_uptilt_comp;
|
||||
uint8_t camera_fov_h;
|
||||
uint8_t camera_fov_v;
|
||||
uint8_t hud_margin_h;
|
||||
|
|
|
@ -186,6 +186,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
.launch_throttle = SETTING_NAV_FW_LAUNCH_THR_DEFAULT,
|
||||
.launch_idle_throttle = SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT, // Motor idle or MOTOR_STOP
|
||||
.launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms
|
||||
.launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms
|
||||
.launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch
|
||||
.launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode
|
||||
.launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode
|
||||
|
@ -1727,7 +1728,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_WAIT(navigationF
|
|||
//allow to leave NAV_LAUNCH_MODE if it has being enabled as feature by moving sticks with low throttle.
|
||||
if (feature(FEATURE_FW_LAUNCH)) {
|
||||
throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC);
|
||||
if ((throttleStatus == THROTTLE_LOW) && (areSticksDeflectedMoreThanPosHoldDeadband())) {
|
||||
if ((throttleStatus == THROTTLE_LOW) && (isRollPitchStickDeflected())) {
|
||||
abortFixedWingLaunch();
|
||||
return NAV_FSM_EVENT_SWITCH_TO_IDLE;
|
||||
}
|
||||
|
@ -2832,13 +2833,23 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData)
|
|||
else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !ARMING_FLAG(ARMED)) {
|
||||
if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) {
|
||||
// Only allow upload next waypoint (continue upload mission) or first waypoint (new mission)
|
||||
static int8_t nonGeoWaypointCount = 0;
|
||||
|
||||
if (wpNumber == (posControl.waypointCount + 1) || wpNumber == 1) {
|
||||
posControl.waypointList[wpNumber - 1] = *wpData;
|
||||
if(wpData->action == NAV_WP_ACTION_JUMP) {
|
||||
posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #)
|
||||
if(wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD || wpData->action == NAV_WP_ACTION_JUMP) {
|
||||
nonGeoWaypointCount += 1;
|
||||
if(wpData->action == NAV_WP_ACTION_JUMP) {
|
||||
posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #)
|
||||
}
|
||||
}
|
||||
|
||||
posControl.waypointCount = wpNumber;
|
||||
posControl.waypointListValid = (wpData->flag == NAV_WP_FLAG_LAST);
|
||||
posControl.geoWaypointCount = posControl.waypointCount - nonGeoWaypointCount;
|
||||
if (posControl.waypointListValid) {
|
||||
nonGeoWaypointCount = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2850,6 +2861,7 @@ void resetWaypointList(void)
|
|||
if (!ARMING_FLAG(ARMED)) {
|
||||
posControl.waypointCount = 0;
|
||||
posControl.waypointListValid = false;
|
||||
posControl.geoWaypointCount = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -264,6 +264,7 @@ typedef struct navConfig_s {
|
|||
uint16_t launch_idle_throttle; // Throttle to keep at launch idle
|
||||
uint16_t launch_throttle; // Launch throttle
|
||||
uint16_t launch_motor_timer; // Time to wait before setting launch_throttle (ms)
|
||||
uint16_t launch_idle_motor_timer; // Time to wait before motor starts at_idle throttle (ms)
|
||||
uint16_t launch_motor_spinup_time; // Time to speed-up motors from idle to launch_throttle (ESC desync prevention)
|
||||
uint16_t launch_end_time; // Time to make the transition from launch angle to leveled and throttle transition from launch throttle to the stick position
|
||||
uint16_t launch_min_time; // Minimum time in launch mode to prevent possible bump of the sticks from leaving launch mode early
|
||||
|
|
|
@ -54,6 +54,7 @@
|
|||
#define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms
|
||||
#define UNUSED(x) ((void)(x))
|
||||
#define FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE "RAISE THE THROTTLE"
|
||||
#define FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE "WAITING FOR IDLE"
|
||||
#define FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION "READY"
|
||||
#define FW_LAUNCH_MESSAGE_TEXT_IN_PROGRESS "MOVE THE STICKS TO ABORT"
|
||||
#define FW_LAUNCH_MESSAGE_TEXT_FINISHING "FINISHING"
|
||||
|
@ -61,6 +62,7 @@
|
|||
typedef enum {
|
||||
FW_LAUNCH_MESSAGE_TYPE_NONE = 0,
|
||||
FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE,
|
||||
FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE,
|
||||
FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION,
|
||||
FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS,
|
||||
FW_LAUNCH_MESSAGE_TYPE_FINISHING
|
||||
|
@ -78,6 +80,7 @@ typedef enum {
|
|||
typedef enum {
|
||||
FW_LAUNCH_STATE_IDLE = 0,
|
||||
FW_LAUNCH_STATE_WAIT_THROTTLE,
|
||||
FW_LAUNCH_STATE_IDLE_MOTOR_DELAY,
|
||||
FW_LAUNCH_STATE_MOTOR_IDLE,
|
||||
FW_LAUNCH_STATE_WAIT_DETECTION,
|
||||
FW_LAUNCH_STATE_DETECTED,
|
||||
|
@ -90,6 +93,7 @@ typedef enum {
|
|||
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE(timeUs_t currentTimeUs);
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs_t currentTimeUs);
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs);
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs);
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_DETECTION(timeUs_t currentTimeUs);
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_DETECTED(timeUs_t currentTimeUs);
|
||||
|
@ -111,6 +115,7 @@ typedef struct fixedWingLaunchData_s {
|
|||
} fixedWingLaunchData_t;
|
||||
|
||||
static EXTENDED_FASTRAM fixedWingLaunchData_t fwLaunch;
|
||||
static bool idleMotorAboutToStart;
|
||||
|
||||
static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE_COUNT] = {
|
||||
|
||||
|
@ -125,19 +130,28 @@ static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE
|
|||
[FW_LAUNCH_STATE_WAIT_THROTTLE] = {
|
||||
.onEntry = fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE,
|
||||
.onEvent = {
|
||||
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE,
|
||||
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_IDLE_MOTOR_DELAY,
|
||||
[FW_LAUNCH_EVENT_GOTO_DETECTION] = FW_LAUNCH_STATE_WAIT_DETECTION
|
||||
},
|
||||
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE
|
||||
},
|
||||
|
||||
[FW_LAUNCH_STATE_IDLE_MOTOR_DELAY] = {
|
||||
.onEntry = fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY,
|
||||
.onEvent = {
|
||||
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE,
|
||||
[FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE
|
||||
},
|
||||
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE
|
||||
},
|
||||
|
||||
[FW_LAUNCH_STATE_MOTOR_IDLE] = {
|
||||
.onEntry = fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE,
|
||||
.onEvent = {
|
||||
[FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_WAIT_DETECTION,
|
||||
[FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE
|
||||
},
|
||||
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE
|
||||
.messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE
|
||||
},
|
||||
|
||||
[FW_LAUNCH_STATE_WAIT_DETECTION] = {
|
||||
|
@ -237,7 +251,7 @@ static inline bool isLaunchMaxAltitudeReached(void)
|
|||
|
||||
static inline bool areSticksMoved(timeMs_t initialTime, timeUs_t currentTimeUs)
|
||||
{
|
||||
return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && areSticksDeflectedMoreThanPosHoldDeadband();
|
||||
return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && isRollPitchStickDeflected();
|
||||
}
|
||||
|
||||
static void resetPidsIfNeeded(void) {
|
||||
|
@ -287,6 +301,24 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs
|
|||
return FW_LAUNCH_EVENT_NONE;
|
||||
}
|
||||
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs)
|
||||
{
|
||||
if (isThrottleLow()) {
|
||||
return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE
|
||||
}
|
||||
|
||||
applyThrottleIdleLogic(true);
|
||||
|
||||
if (currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) {
|
||||
idleMotorAboutToStart = false;
|
||||
return FW_LAUNCH_EVENT_SUCCESS;
|
||||
}
|
||||
// 5 second warning motor about to start at idle, changes Beeper sound
|
||||
idleMotorAboutToStart = navConfig()->fw.launch_idle_motor_timer - currentStateElapsedMs(currentTimeUs) < 5000;
|
||||
|
||||
return FW_LAUNCH_EVENT_NONE;
|
||||
}
|
||||
|
||||
static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs)
|
||||
{
|
||||
if (isThrottleLow()) {
|
||||
|
@ -403,7 +435,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_FINISH(timeUs_t curr
|
|||
const timeMs_t elapsedTimeMs = currentStateElapsedMs(currentTimeUs);
|
||||
const timeMs_t endTimeMs = navConfig()->fw.launch_end_time;
|
||||
|
||||
if (areSticksDeflectedMoreThanPosHoldDeadband()) {
|
||||
if (isRollPitchStickDeflected()) {
|
||||
return FW_LAUNCH_EVENT_ABORT; // cancel the launch and do the FW_LAUNCH_STATE_IDLE state
|
||||
}
|
||||
if (elapsedTimeMs > endTimeMs) {
|
||||
|
@ -441,7 +473,11 @@ void applyFixedWingLaunchController(timeUs_t currentTimeUs)
|
|||
beeper(BEEPER_LAUNCH_MODE_LOW_THROTTLE);
|
||||
}
|
||||
else {
|
||||
beeper(BEEPER_LAUNCH_MODE_ENABLED);
|
||||
if (idleMotorAboutToStart) {
|
||||
beeper(BEEPER_LAUNCH_MODE_IDLE_START);
|
||||
} else {
|
||||
beeper(BEEPER_LAUNCH_MODE_ENABLED);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -476,6 +512,9 @@ const char * fixedWingLaunchStateMessage(void)
|
|||
case FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE:
|
||||
return FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE;
|
||||
|
||||
case FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE:
|
||||
return FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE;
|
||||
|
||||
case FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION:
|
||||
return FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION;
|
||||
|
||||
|
|
3
src/main/navigation/navigation_private.h
Executable file → Normal file
3
src/main/navigation/navigation_private.h
Executable file → Normal file
|
@ -356,8 +356,9 @@ typedef struct {
|
|||
navWaypoint_t waypointList[NAV_MAX_WAYPOINTS];
|
||||
bool waypointListValid;
|
||||
int8_t waypointCount;
|
||||
int8_t geoWaypointCount; // total geospatial WPs in mission
|
||||
|
||||
navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation
|
||||
navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation
|
||||
int8_t activeWaypointIndex;
|
||||
float wpInitialAltitude; // Altitude at start of WP
|
||||
float wpInitialDistance; // Distance when starting flight to WP
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-function"
|
||||
#define MAVLINK_COMM_NUM_BUFFERS 1
|
||||
#include "common/mavlink.h"
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
|
|
|
@ -299,7 +299,9 @@ void FAST_CODE NOINLINE scheduler(void)
|
|||
#if defined(SCHEDULER_DEBUG)
|
||||
DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs - taskExecutionTime); // time spent in scheduler
|
||||
#endif
|
||||
} else {
|
||||
}
|
||||
|
||||
if (!selectedTask || forcedRealTimeTask) {
|
||||
// Execute system real-time callbacks and account for them to SYSTEM account
|
||||
const timeUs_t currentTimeBeforeTaskCall = micros();
|
||||
taskRunRealtimeCallbacks(currentTimeBeforeTaskCall);
|
||||
|
|
|
@ -111,7 +111,7 @@ STATIC_FASTRAM alphaBetaGammaFilter_t abgFilter[XYZ_AXIS_COUNT];
|
|||
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 13);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 14);
|
||||
|
||||
PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
|
||||
.gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT,
|
||||
|
|
|
@ -63,7 +63,7 @@ typedef struct gyroConfig_s {
|
|||
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
|
||||
uint16_t looptime; // imu loop time in us
|
||||
uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
|
||||
uint8_t gyro_anti_aliasing_lpf_hz;
|
||||
uint16_t gyro_anti_aliasing_lpf_hz;
|
||||
uint8_t gyro_anti_aliasing_lpf_type;
|
||||
#ifdef USE_DUAL_GYRO
|
||||
uint8_t gyro_to_use;
|
||||
|
|
|
@ -92,20 +92,20 @@
|
|||
#define USE_SPI_DEVICE_2 //OSD
|
||||
#define USE_SPI_DEVICE_4 //ICM20689
|
||||
|
||||
#define SPI1_NSS_PIN PA4//
|
||||
#define SPI1_SCK_PIN PA5//
|
||||
#define SPI1_MISO_PIN PA6//
|
||||
#define SPI1_MOSI_PIN PA7//
|
||||
#define SPI1_NSS_PIN PA4
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define SPI2_NSS_PIN PB12//
|
||||
#define SPI2_SCK_PIN PB13///
|
||||
#define SPI2_MISO_PIN PB14//
|
||||
#define SPI2_MOSI_PIN PB15//
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define SPI4_NSS_PIN PE4//
|
||||
#define SPI4_SCK_PIN PE2//
|
||||
#define SPI4_MISO_PIN PE5//
|
||||
#define SPI4_MOSI_PIN PE6//
|
||||
#define SPI4_NSS_PIN PE4
|
||||
#define SPI4_SCK_PIN PE2
|
||||
#define SPI4_MISO_PIN PE5
|
||||
#define SPI4_MOSI_PIN PE6
|
||||
|
||||
#define USE_OSD
|
||||
|
||||
|
@ -128,13 +128,28 @@
|
|||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10
|
||||
#define I2C2_SDA PB11
|
||||
|
||||
//External I2C bus is different than internal one
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C2
|
||||
#define DEFAULT_I2C_BUS BUS_I2C2
|
||||
|
||||
#else
|
||||
|
||||
//External I2C bus is the same as interal one
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
#define DEFAULT_I2C_BUS BUS_I2C1
|
||||
|
||||
#endif
|
||||
|
||||
#define USE_BARO
|
||||
#define USE_BARO_BMP280
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_MAG3110
|
||||
|
@ -142,14 +157,10 @@
|
|||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC2//
|
||||
#define ADC_CHANNEL_2_PIN PC3//
|
||||
#define ADC_CHANNEL_3_PIN PC5//
|
||||
#define ADC_CHANNEL_1_PIN PC2
|
||||
#define ADC_CHANNEL_2_PIN PC3
|
||||
#define ADC_CHANNEL_3_PIN PC5
|
||||
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_2
|
||||
|
|
|
@ -89,6 +89,7 @@
|
|||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-function"
|
||||
#define MAVLINK_COMM_NUM_BUFFERS 1
|
||||
#include "common/mavlink.h"
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
|
@ -326,7 +327,14 @@ void checkMAVLinkTelemetryState(void)
|
|||
static void mavlinkSendMessage(void)
|
||||
{
|
||||
uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
|
||||
if (telemetryConfig()->mavlink.version == 1) mavSendMsg.magic = MAVLINK_STX_MAVLINK1;
|
||||
|
||||
mavlink_status_t* chan_state = mavlink_get_channel_status(MAVLINK_COMM_0);
|
||||
if (telemetryConfig()->mavlink.version == 1) {
|
||||
chan_state->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
||||
} else {
|
||||
chan_state->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
||||
}
|
||||
|
||||
int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavSendMsg);
|
||||
|
||||
for (int i = 0; i < msgLength; i++) {
|
||||
|
@ -502,8 +510,9 @@ void mavlinkSendRCChannelsAndRSSI(void)
|
|||
GET_CHANNEL_VALUE(6),
|
||||
// chan8_raw RC channel 8 value, in microseconds
|
||||
GET_CHANNEL_VALUE(7),
|
||||
// rssi Receive signal strength indicator, 0: 0%, 255: 100%
|
||||
scaleRange(getRSSI(), 0, 1023, 0, 255));
|
||||
// rssi Receive signal strength indicator, 0: 0%, 254: 100%
|
||||
//https://github.com/mavlink/mavlink/issues/1027
|
||||
scaleRange(getRSSI(), 0, 1023, 0, 254));
|
||||
#undef GET_CHANNEL_VALUE
|
||||
|
||||
mavlinkSendMessage();
|
||||
|
|
|
@ -907,8 +907,8 @@ class Generator
|
|||
unsigned = !$~[:unsigned].empty?
|
||||
bitsize = $~[:bitsize].to_i
|
||||
type_range = unsigned ? 0..(2**bitsize-1) : (-2**(bitsize-1)+1)..(2**(bitsize-1)-1)
|
||||
min = type_range.min if min =~ /\AU?INT\d+_MIN\Z/
|
||||
max = type_range.max if max =~ /\AU?INT\d+_MAX\Z/
|
||||
min = type_range.min if min.to_s =~ /\AU?INT\d+_MIN\Z/
|
||||
max = type_range.max if max.to_s =~ /\AU?INT\d+_MAX\Z/
|
||||
raise "Member #{name} default value has an invalid type, integer or symbol expected" unless default_value.is_a? Integer or default_value.is_a? Symbol
|
||||
raise "Member #{name} default value is outside type's storage range, min #{type_range.min}, max #{type_range.max}" unless default_value.is_a? Symbol or type_range === default_value
|
||||
raise "Numeric member #{name} doesn't have maximum value defined" unless member.has_key? 'max'
|
||||
|
|
|
@ -38,7 +38,7 @@ def parse_settings_yaml():
|
|||
with open(SETTINGS_YAML_PATH, "r") as settings_yaml:
|
||||
return yaml.load(settings_yaml, Loader=yaml.Loader)
|
||||
|
||||
def generate_md_table_from_yaml(settings_yaml):
|
||||
def generate_md_from_yaml(settings_yaml):
|
||||
"""Generate a sorted markdown table with description & default value for each setting"""
|
||||
params = {}
|
||||
|
||||
|
@ -84,20 +84,19 @@ def generate_md_table_from_yaml(settings_yaml):
|
|||
"max": member["max"] if "max" in member else ""
|
||||
}
|
||||
|
||||
# MD table header
|
||||
md_table_lines = [
|
||||
"| Variable Name | Default Value | Min | Max | Description |\n",
|
||||
"| ------------- | ------------- | --- | --- | ----------- |\n",
|
||||
]
|
||||
|
||||
# Sort the settings by name and build the rows of the table
|
||||
# Sort the settings by name and build the doc
|
||||
output_lines = []
|
||||
for param in sorted(params.items()):
|
||||
md_table_lines.append("| {} | {} | {} | {} | {} |\n".format(
|
||||
param[0], param[1]['default'], param[1]['min'], param[1]['max'], param[1]['description']
|
||||
))
|
||||
output_lines.extend([
|
||||
f"### {param[0]}\n\n",
|
||||
f"{param[1]['description'] if param[1]['description'] else '_// TODO_'}\n\n",
|
||||
"| Default | Min | Max |\n| --- | --- | --- |\n",
|
||||
f"| {param[1]['default']} | {param[1]['min']} | {param[1]['max']} |\n\n",
|
||||
"---\n\n"
|
||||
])
|
||||
|
||||
# Return the assembled table
|
||||
return md_table_lines
|
||||
# Return the assembled doc body
|
||||
return output_lines
|
||||
|
||||
def write_settings_md(lines):
|
||||
"""Write the contents of the CLI settings docs"""
|
||||
|
@ -185,9 +184,9 @@ if __name__ == "__main__":
|
|||
defaults_match = check_defaults(settings_yaml)
|
||||
quit(0 if defaults_match else 1)
|
||||
|
||||
md_table_lines = generate_md_table_from_yaml(settings_yaml)
|
||||
settings_md_lines = \
|
||||
["# CLI Variable Reference\n", "\n" ] + \
|
||||
md_table_lines + \
|
||||
["\n", "> Note: this table is autogenerated. Do not edit it manually."]
|
||||
write_settings_md(settings_md_lines)
|
||||
output_lines = generate_md_from_yaml(settings_yaml)
|
||||
output_lines = [
|
||||
"# CLI Variable Reference\n\n",
|
||||
"> Note: this document is autogenerated. Do not edit it manually.\n\n"
|
||||
] + output_lines
|
||||
write_settings_md(output_lines)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue