1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-13 19:40:27 +03:00

Unfuck rebase

This commit is contained in:
Darren Lines 2024-01-13 09:50:17 +00:00
parent ac748788e6
commit 1e6a20f592
15 changed files with 16 additions and 167 deletions

View file

@ -104,9 +104,6 @@ TailSitter is supported by add a 90deg offset to the board alignment. Set the bo
- Rate Settings - Rate Settings
- ······· - ·······
### TailSitter support
TailSitter is supported by add a 90deg offset to the board alignment. Set the board aliment normally in the mixer_profile for FW mode(`set platform_type = AIRPLANE`), The motor trust axis should be same direction as the airplane nose. Then, in the mixer_profile for takeoff and landing `set platform_type = TAILSITTER`. The `TAILSITTER` platform type is same as `MULTIROTOR` platform type, expect for a 90 deg board alignment offset. In `TAILSITTER` mixer_profile, when motor trust/airplane nose is pointing to the sky, 'airplane bottom'/'multi rotor front' should facing forward in model preview. Set the motor/servo mixer according to multirotor orientation, Model should roll around geography's longitudinal axis, the roll axis of `TAILSITTER` will be yaw axis of `AIRPLANE`. In addition, When `MIXER TRANSITION` input is activated, a 45deg offset will be add to the target angle for angle mode.
## Happy flying ## Happy flying
Remember that this is currently an emerging capability: Remember that this is currently an emerging capability:

View file

@ -5812,16 +5812,6 @@ Delay before disarming when requested by switch (ms) [0-1000]
--- ---
### tailsitter_orientation_offset
Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode
| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |
---
### telemetry_halfduplex ### telemetry_halfduplex
S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details

View file

@ -344,11 +344,6 @@ static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[2] = hmsc->bot_data[2] | (1 << 7);
}
return 0; return 0;
} }
@ -372,11 +367,6 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[3] = hmsc->bot_data[3] | (1 << 7);
}
return 0; return 0;
} }

View file

@ -348,11 +348,6 @@ static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[2] = hmsc->bot_data[2] | (1 << 7);
}
return 0; return 0;
} }
@ -377,11 +372,6 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[3] = hmsc->bot_data[3] | (1 << 7);
}
return 0; return 0;
} }

View file

@ -347,11 +347,6 @@ static int8_t SCSI_ModeSense6(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *p
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[2] = hmsc->bot_data[2] | (1 << 7);
}
return 0; return 0;
} }
@ -377,11 +372,6 @@ static int8_t SCSI_ModeSense10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[3] = hmsc->bot_data[3] | (1 << 7);
}
return 0; return 0;
} }

View file

@ -1188,14 +1188,6 @@ groups:
field: mixer_config.switchTransitionTimer field: mixer_config.switchTransitionTimer
min: 0 min: 0
max: 200 max: 200
- name: tailsitter_orientation_offset
description: "Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode"
default_value: OFF
field: mixer_config.tailsitterOrientationOffset
type: bool
- name: PG_REVERSIBLE_MOTORS_CONFIG - name: PG_REVERSIBLE_MOTORS_CONFIG
type: reversibleMotorsConfig_t type: reversibleMotorsConfig_t
members: members:

View file

@ -704,33 +704,6 @@ static void imuCalculateTurnRateacceleration(fpVector3_t *vEstcentrifugalAccelBF
lastspeed = currentspeed; lastspeed = currentspeed;
} }
fpQuaternion_t* getTailSitterQuaternion(bool normal2tail){
static bool firstRun = true;
static fpQuaternion_t qNormal2Tail;
static fpQuaternion_t qTail2Normal;
if(firstRun){
fpAxisAngle_t axisAngle;
axisAngle.axis.x = 0;
axisAngle.axis.y = 1;
axisAngle.axis.z = 0;
axisAngle.angle = DEGREES_TO_RADIANS(-90);
axisAngleToQuaternion(&qNormal2Tail, &axisAngle);
quaternionConjugate(&qTail2Normal, &qNormal2Tail);
firstRun = false;
}
return normal2tail ? &qNormal2Tail : &qTail2Normal;
}
void imuUpdateTailSitter(void)
{
static bool lastTailSitter=false;
if (((bool)STATE(TAILSITTER)) != lastTailSitter){
fpQuaternion_t* rotation_for_tailsitter= getTailSitterQuaternion(STATE(TAILSITTER));
quaternionMultiply(&orientation, &orientation, rotation_for_tailsitter);
}
lastTailSitter = STATE(TAILSITTER);
}
static void imuCalculateEstimatedAttitude(float dT) static void imuCalculateEstimatedAttitude(float dT)
{ {
#if defined(USE_MAG) #if defined(USE_MAG)
@ -827,7 +800,6 @@ static void imuCalculateEstimatedAttitude(float dT)
useCOG, courseOverGround, useCOG, courseOverGround,
accWeight, accWeight,
magWeight); magWeight);
imuUpdateTailSitter();
imuUpdateEulerAngles(); imuUpdateEulerAngles();
} }

View file

@ -161,7 +161,6 @@ void mixerUpdateStateFlags(void)
DISABLE_STATE(BOAT); DISABLE_STATE(BOAT);
DISABLE_STATE(AIRPLANE); DISABLE_STATE(AIRPLANE);
DISABLE_STATE(MOVE_FORWARD_ONLY); DISABLE_STATE(MOVE_FORWARD_ONLY);
DISABLE_STATE(TAILSITTER);
if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) { if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) {
ENABLE_STATE(FIXED_WING_LEGACY); ENABLE_STATE(FIXED_WING_LEGACY);
@ -187,12 +186,6 @@ void mixerUpdateStateFlags(void)
ENABLE_STATE(ALTITUDE_CONTROL); ENABLE_STATE(ALTITUDE_CONTROL);
} }
if (currentMixerConfig.tailsitterOrientationOffset) {
ENABLE_STATE(TAILSITTER);
} else {
DISABLE_STATE(TAILSITTER);
}
if (currentMixerConfig.hasFlaps) { if (currentMixerConfig.hasFlaps) {
ENABLE_STATE(FLAPERON_AVAILABLE); ENABLE_STATE(FLAPERON_AVAILABLE);
} else { } else {

View file

@ -53,7 +53,6 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance)
.PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT, .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT,
.automated_switch = SETTING_MIXER_AUTOMATED_SWITCH_DEFAULT, .automated_switch = SETTING_MIXER_AUTOMATED_SWITCH_DEFAULT,
.switchTransitionTimer = SETTING_MIXER_SWITCH_TRANS_TIMER_DEFAULT, .switchTransitionTimer = SETTING_MIXER_SWITCH_TRANS_TIMER_DEFAULT,
.tailsitterOrientationOffset = SETTING_TAILSITTER_ORIENTATION_OFFSET_DEFAULT,
}); });
for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++)
{ {

View file

@ -18,7 +18,6 @@ typedef struct mixerConfig_s {
bool PIDProfileLinking; bool PIDProfileLinking;
bool automated_switch; bool automated_switch;
int16_t switchTransitionTimer; int16_t switchTransitionTimer;
bool tailsitterOrientationOffset;
} mixerConfig_t; } mixerConfig_t;
typedef struct mixerProfile_s { typedef struct mixerProfile_s {
mixerConfig_t mixer_config; mixerConfig_t mixer_config;

View file

@ -586,11 +586,7 @@ int16_t angleFreefloatDeadband(int16_t deadband, flight_dynamics_index_t axis)
static float computePidLevelTarget(flight_dynamics_index_t axis) { static float computePidLevelTarget(flight_dynamics_index_t axis) {
// This is ROLL/PITCH, run ANGLE/HORIZON controllers // This is ROLL/PITCH, run ANGLE/HORIZON controllers
#ifdef USE_PROGRAMMING_FRAMEWORK
float angleTarget = pidRcCommandToAngle(getRcCommandOverride(rcCommand, axis), pidProfile()->max_angle_inclination[axis]);
#else
float angleTarget = pidRcCommandToAngle(rcCommand[axis], pidProfile()->max_angle_inclination[axis]); float angleTarget = pidRcCommandToAngle(rcCommand[axis], pidProfile()->max_angle_inclination[axis]);
#endif
// Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle // Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle
if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) { if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) {
@ -1146,6 +1142,7 @@ void FAST_CODE pidController(float dT)
} }
for (int axis = 0; axis < 3; axis++) { for (int axis = 0; axis < 3; axis++) {
// Step 1: Calculate gyro rates
pidState[axis].gyroRate = gyro.gyroADCf[axis]; pidState[axis].gyroRate = gyro.gyroADCf[axis];
// Step 2: Read target // Step 2: Read target
@ -1183,11 +1180,6 @@ void FAST_CODE pidController(float dT)
// If axis angle override, get the correct angle from Logic Conditions // If axis angle override, get the correct angle from Logic Conditions
float angleTarget = getFlightAxisAngleOverride(axis, computePidLevelTarget(axis)); float angleTarget = getFlightAxisAngleOverride(axis, computePidLevelTarget(axis));
//apply 45 deg offset for tailsitter when isMixerTransitionMixing is activated
if (STATE(TAILSITTER) && isMixerTransitionMixing && axis == FD_PITCH){
angleTarget += DEGREES_TO_DECIDEGREES(45);
}
if (STATE(AIRPLANE)) { // update anglehold mode if (STATE(AIRPLANE)) { // update anglehold mode
updateAngleHold(&angleTarget, axis); updateAngleHold(&angleTarget, axis);
} }

View file

@ -578,48 +578,6 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page)
case (SYM_AH_V_START+4): case (SYM_AH_V_START+4):
case (SYM_AH_V_START+5): case (SYM_AH_V_START+5):
return BF_SYM_AH_BAR9_4; return BF_SYM_AH_BAR9_4;
// BF for ESP_RADAR Symbols
case SYM_HUD_CARDINAL:
return BF_SYM_ARROW_SOUTH;
case SYM_HUD_CARDINAL + 1:
return BF_SYM_ARROW_16;
case SYM_HUD_CARDINAL + 2:
return BF_SYM_ARROW_15;
case SYM_HUD_CARDINAL + 3:
return BF_SYM_ARROW_WEST;
case SYM_HUD_CARDINAL + 4:
return BF_SYM_ARROW_12;
case SYM_HUD_CARDINAL + 5:
return BF_SYM_ARROW_11;
case SYM_HUD_CARDINAL + 6:
return BF_SYM_ARROW_NORTH;
case SYM_HUD_CARDINAL + 7:
return BF_SYM_ARROW_7;
case SYM_HUD_CARDINAL + 8:
return BF_SYM_ARROW_6;
case SYM_HUD_CARDINAL + 9:
return BF_SYM_ARROW_EAST;
case SYM_HUD_CARDINAL + 10:
return BF_SYM_ARROW_3;
case SYM_HUD_CARDINAL + 11:
return BF_SYM_ARROW_2;
case SYM_HUD_ARROWS_R3:
return BF_SYM_AH_RIGHT;
case SYM_HUD_ARROWS_L3:
return BF_SYM_AH_LEFT;
case SYM_HUD_SIGNAL_0:
return BF_SYM_AH_BAR9_1;
case SYM_HUD_SIGNAL_1:
return BF_SYM_AH_BAR9_3;
case SYM_HUD_SIGNAL_2:
return BF_SYM_AH_BAR9_4;
case SYM_HUD_SIGNAL_3:
return BF_SYM_AH_BAR9_5;
case SYM_HUD_SIGNAL_4:
return BF_SYM_AH_BAR9_7;
/* /*
case SYM_VARIO_UP_2A: case SYM_VARIO_UP_2A:
return BF_SYM_VARIO_UP_2A; return BF_SYM_VARIO_UP_2A;

View file

@ -28,7 +28,6 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "config/parameter_group_ids.h" #include "config/parameter_group_ids.h"
#include "fc/runtime_config.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -46,7 +45,6 @@
static bool standardBoardAlignment = true; // board orientation correction static bool standardBoardAlignment = true; // board orientation correction
static fpMat3_t boardRotMatrix; static fpMat3_t boardRotMatrix;
static fpMat3_t tailRotMatrix;
// no template required since defaults are zero // no template required since defaults are zero
PG_REGISTER(boardAlignment_t, boardAlignment, PG_BOARD_ALIGNMENT, 0); PG_REGISTER(boardAlignment_t, boardAlignment, PG_BOARD_ALIGNMENT, 0);
@ -58,19 +56,19 @@ static bool isBoardAlignmentStandard(const boardAlignment_t *boardAlignment)
void initBoardAlignment(void) void initBoardAlignment(void)
{ {
standardBoardAlignment=isBoardAlignmentStandard(boardAlignment()); if (isBoardAlignmentStandard(boardAlignment())) {
standardBoardAlignment = true;
} else {
fp_angles_t rotationAngles; fp_angles_t rotationAngles;
standardBoardAlignment = false;
rotationAngles.angles.roll = DECIDEGREES_TO_RADIANS(boardAlignment()->rollDeciDegrees ); rotationAngles.angles.roll = DECIDEGREES_TO_RADIANS(boardAlignment()->rollDeciDegrees );
rotationAngles.angles.pitch = DECIDEGREES_TO_RADIANS(boardAlignment()->pitchDeciDegrees); rotationAngles.angles.pitch = DECIDEGREES_TO_RADIANS(boardAlignment()->pitchDeciDegrees);
rotationAngles.angles.yaw = DECIDEGREES_TO_RADIANS(boardAlignment()->yawDeciDegrees ); rotationAngles.angles.yaw = DECIDEGREES_TO_RADIANS(boardAlignment()->yawDeciDegrees );
rotationMatrixFromAngles(&boardRotMatrix, &rotationAngles); rotationMatrixFromAngles(&boardRotMatrix, &rotationAngles);
fp_angles_t tailSitter_rotationAngles; }
tailSitter_rotationAngles.angles.roll = DECIDEGREES_TO_RADIANS(0);
tailSitter_rotationAngles.angles.pitch = DECIDEGREES_TO_RADIANS(900);
tailSitter_rotationAngles.angles.yaw = DECIDEGREES_TO_RADIANS(0);
rotationMatrixFromAngles(&tailRotMatrix, &tailSitter_rotationAngles);
} }
void updateBoardAlignment(int16_t roll, int16_t pitch) void updateBoardAlignment(int16_t roll, int16_t pitch)
@ -87,23 +85,15 @@ void updateBoardAlignment(int16_t roll, int16_t pitch)
initBoardAlignment(); initBoardAlignment();
} }
void applyTailSitterAlignment(fpVector3_t *fpVec)
{
if (!STATE(TAILSITTER)) {
return;
}
rotationMatrixRotateVector(fpVec, fpVec, &tailRotMatrix);
}
void applyBoardAlignment(float *vec) void applyBoardAlignment(float *vec)
{ {
if (standardBoardAlignment && (!STATE(TAILSITTER))) { if (standardBoardAlignment) {
return; return;
} }
fpVector3_t fpVec = { .v = { vec[X], vec[Y], vec[Z] } }; fpVector3_t fpVec = { .v = { vec[X], vec[Y], vec[Z] } };
rotationMatrixRotateVector(&fpVec, &fpVec, &boardRotMatrix); rotationMatrixRotateVector(&fpVec, &fpVec, &boardRotMatrix);
applyTailSitterAlignment(&fpVec);
vec[X] = lrintf(fpVec.x); vec[X] = lrintf(fpVec.x);
vec[Y] = lrintf(fpVec.y); vec[Y] = lrintf(fpVec.y);
vec[Z] = lrintf(fpVec.z); vec[Z] = lrintf(fpVec.z);

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "common/vector.h"
typedef struct boardAlignment_s { typedef struct boardAlignment_s {
int16_t rollDeciDegrees; int16_t rollDeciDegrees;
@ -32,4 +31,3 @@ void initBoardAlignment(void);
void updateBoardAlignment(int16_t roll, int16_t pitch); void updateBoardAlignment(int16_t roll, int16_t pitch);
void applySensorAlignment(float * dest, float * src, uint8_t rotation); void applySensorAlignment(float * dest, float * src, uint8_t rotation);
void applyBoardAlignment(float *vec); void applyBoardAlignment(float *vec);
void applyTailSitterAlignment(fpVector3_t *vec);

View file

@ -472,7 +472,6 @@ void compassUpdate(timeUs_t currentTimeUs)
fpVector3_t rotated; fpVector3_t rotated;
rotationMatrixRotateVector(&rotated, &v, &mag.dev.magAlign.externalRotation); rotationMatrixRotateVector(&rotated, &v, &mag.dev.magAlign.externalRotation);
applyTailSitterAlignment(&rotated);
mag.magADC[X] = rotated.x; mag.magADC[X] = rotated.x;
mag.magADC[Y] = rotated.y; mag.magADC[Y] = rotated.y;
mag.magADC[Z] = rotated.z; mag.magADC[Z] = rotated.z;