mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 19:40:31 +03:00
part 3 of the great sensor axis unfucking. careful flight testing may commence.
git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@400 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
05ced4c784
commit
71772f137b
5 changed files with 9 additions and 5 deletions
|
@ -124,6 +124,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "align_gyro", VAR_UINT8, &mcfg.gyro_align, 0, 8 },
|
{ "align_gyro", VAR_UINT8, &mcfg.gyro_align, 0, 8 },
|
||||||
{ "align_acc", VAR_UINT8, &mcfg.acc_align, 0, 8 },
|
{ "align_acc", VAR_UINT8, &mcfg.acc_align, 0, 8 },
|
||||||
{ "align_mag", VAR_UINT8, &mcfg.mag_align, 0, 8 },
|
{ "align_mag", VAR_UINT8, &mcfg.mag_align, 0, 8 },
|
||||||
|
{ "yaw_control_direction", VAR_INT8, &mcfg.yaw_control_direction, -1, 1 },
|
||||||
{ "acc_hardware", VAR_UINT8, &mcfg.acc_hardware, 0, 4 },
|
{ "acc_hardware", VAR_UINT8, &mcfg.acc_hardware, 0, 4 },
|
||||||
{ "moron_threshold", VAR_UINT8, &mcfg.moron_threshold, 0, 128 },
|
{ "moron_threshold", VAR_UINT8, &mcfg.moron_threshold, 0, 128 },
|
||||||
{ "gyro_lpf", VAR_UINT16, &mcfg.gyro_lpf, 0, 256 },
|
{ "gyro_lpf", VAR_UINT16, &mcfg.gyro_lpf, 0, 256 },
|
||||||
|
|
|
@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles
|
||||||
config_t cfg; // profile config struct
|
config_t cfg; // profile config struct
|
||||||
const char rcChannelLetters[] = "AERT1234";
|
const char rcChannelLetters[] = "AERT1234";
|
||||||
|
|
||||||
static const uint8_t EEPROM_CONF_VERSION = 50;
|
static const uint8_t EEPROM_CONF_VERSION = 51;
|
||||||
static uint32_t enabledSensors = 0;
|
static uint32_t enabledSensors = 0;
|
||||||
static void resetConf(void);
|
static void resetConf(void);
|
||||||
|
|
||||||
|
@ -181,6 +181,7 @@ static void resetConf(void)
|
||||||
mcfg.acc_align = ALIGN_DEFAULT;
|
mcfg.acc_align = ALIGN_DEFAULT;
|
||||||
mcfg.mag_align = ALIGN_DEFAULT;
|
mcfg.mag_align = ALIGN_DEFAULT;
|
||||||
mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect
|
mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||||
|
mcfg.yaw_control_direction = 1;
|
||||||
mcfg.moron_threshold = 32;
|
mcfg.moron_threshold = 32;
|
||||||
mcfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
|
mcfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
|
||||||
mcfg.vbatscale = 110;
|
mcfg.vbatscale = 110;
|
||||||
|
|
|
@ -321,17 +321,17 @@ void mixTable(void)
|
||||||
// motors for non-servo mixes
|
// motors for non-servo mixes
|
||||||
if (numberMotor > 1)
|
if (numberMotor > 1)
|
||||||
for (i = 0; i < numberMotor; i++)
|
for (i = 0; i < numberMotor; i++)
|
||||||
motor[i] = rcCommand[THROTTLE] * currentMixer[i].throttle + axisPID[PITCH] * currentMixer[i].pitch + axisPID[ROLL] * currentMixer[i].roll + cfg.yaw_direction * axisPID[YAW] * currentMixer[i].yaw;
|
motor[i] = rcCommand[THROTTLE] * currentMixer[i].throttle + axisPID[PITCH] * currentMixer[i].pitch + axisPID[ROLL] * currentMixer[i].roll + -cfg.yaw_direction * axisPID[YAW] * currentMixer[i].yaw;
|
||||||
|
|
||||||
// airplane / servo mixes
|
// airplane / servo mixes
|
||||||
switch (mcfg.mixerConfiguration) {
|
switch (mcfg.mixerConfiguration) {
|
||||||
case MULTITYPE_BI:
|
case MULTITYPE_BI:
|
||||||
servo[4] = constrain(1500 + (cfg.yaw_direction * axisPID[YAW]) + axisPID[PITCH], 1020, 2000); //LEFT
|
servo[4] = constrain(1500 + (-cfg.yaw_direction * axisPID[YAW]) + axisPID[PITCH], 1020, 2000); //LEFT
|
||||||
servo[5] = constrain(1500 + (cfg.yaw_direction * axisPID[YAW]) - axisPID[PITCH], 1020, 2000); //RIGHT
|
servo[5] = constrain(1500 + (-cfg.yaw_direction * axisPID[YAW]) - axisPID[PITCH], 1020, 2000); //RIGHT
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MULTITYPE_TRI:
|
case MULTITYPE_TRI:
|
||||||
servo[5] = constrain(cfg.tri_yaw_middle + cfg.yaw_direction * axisPID[YAW], cfg.tri_yaw_min, cfg.tri_yaw_max); //REAR
|
servo[5] = constrain(cfg.tri_yaw_middle + -cfg.yaw_direction * axisPID[YAW], cfg.tri_yaw_min, cfg.tri_yaw_max); //REAR
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MULTITYPE_GIMBAL:
|
case MULTITYPE_GIMBAL:
|
||||||
|
|
1
src/mw.c
1
src/mw.c
|
@ -125,6 +125,7 @@ void annexCode(void)
|
||||||
prop1 = 100 - (uint16_t) cfg.rollPitchRate * tmp / 500;
|
prop1 = 100 - (uint16_t) cfg.rollPitchRate * tmp / 500;
|
||||||
prop1 = (uint16_t) prop1 *prop2 / 100;
|
prop1 = (uint16_t) prop1 *prop2 / 100;
|
||||||
} else { // YAW
|
} else { // YAW
|
||||||
|
tmp *= -mcfg.yaw_control_direction; //change control direction for yaw needed with new gyro orientation
|
||||||
if (cfg.yawdeadband) {
|
if (cfg.yawdeadband) {
|
||||||
if (tmp > cfg.yawdeadband) {
|
if (tmp > cfg.yawdeadband) {
|
||||||
tmp -= cfg.yawdeadband;
|
tmp -= cfg.yawdeadband;
|
||||||
|
|
1
src/mw.h
1
src/mw.h
|
@ -254,6 +254,7 @@ typedef struct master_t {
|
||||||
sensor_align_e gyro_align; // gyro alignment
|
sensor_align_e gyro_align; // gyro alignment
|
||||||
sensor_align_e acc_align; // acc alignment
|
sensor_align_e acc_align; // acc alignment
|
||||||
sensor_align_e mag_align; // mag alignment
|
sensor_align_e mag_align; // mag alignment
|
||||||
|
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
|
||||||
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||||
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
|
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
|
||||||
uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
|
uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue