added max_angle_inclination to CLI to configure (default) 50 degree max inclination. configurable between 10 and 90 (100..900 in cli)
This commit is contained in:
parent
9d421b4a67
commit
202fc17608
|
@ -145,6 +145,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "align_board_yaw", VAR_INT16, &mcfg.board_align_yaw, -180, 360 },
|
{ "align_board_yaw", VAR_INT16, &mcfg.board_align_yaw, -180, 360 },
|
||||||
{ "yaw_control_direction", VAR_INT8, &mcfg.yaw_control_direction, -1, 1 },
|
{ "yaw_control_direction", VAR_INT8, &mcfg.yaw_control_direction, -1, 1 },
|
||||||
{ "acc_hardware", VAR_UINT8, &mcfg.acc_hardware, 0, 5 },
|
{ "acc_hardware", VAR_UINT8, &mcfg.acc_hardware, 0, 5 },
|
||||||
|
{ "max_angle_inclination", VAR_UINT16, &mcfg.max_angle_inclination, 100, 900 },
|
||||||
{ "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 },
|
||||||
{ "gyro_cmpf_factor", VAR_UINT16, &mcfg.gyro_cmpf_factor, 100, 1000 },
|
{ "gyro_cmpf_factor", VAR_UINT16, &mcfg.gyro_cmpf_factor, 100, 1000 },
|
||||||
|
|
|
@ -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 = 57;
|
static const uint8_t EEPROM_CONF_VERSION = 58;
|
||||||
static uint32_t enabledSensors = 0;
|
static uint32_t enabledSensors = 0;
|
||||||
static void resetConf(void);
|
static void resetConf(void);
|
||||||
|
|
||||||
|
@ -184,6 +184,7 @@ static void resetConf(void)
|
||||||
mcfg.board_align_pitch = 0;
|
mcfg.board_align_pitch = 0;
|
||||||
mcfg.board_align_yaw = 0;
|
mcfg.board_align_yaw = 0;
|
||||||
mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect
|
mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||||
|
mcfg.max_angle_inclination = 500; // 50 degrees
|
||||||
mcfg.yaw_control_direction = 1;
|
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
|
||||||
|
|
6
src/mw.c
6
src/mw.c
|
@ -302,7 +302,7 @@ static void pidMultiWii(void)
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2) { // MODE relying on ACC
|
if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2) { // MODE relying on ACC
|
||||||
// 50 degrees max inclination
|
// 50 degrees max inclination
|
||||||
errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -500, +500) - angle[axis] + cfg.angleTrim[axis];
|
errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int)mcfg.max_angle_inclination), +mcfg.max_angle_inclination) - angle[axis] + cfg.angleTrim[axis];
|
||||||
PTermACC = errorAngle * cfg.P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
|
PTermACC = errorAngle * cfg.P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
|
||||||
PTermACC = constrain(PTermACC, -cfg.D8[PIDLEVEL] * 5, +cfg.D8[PIDLEVEL] * 5);
|
PTermACC = constrain(PTermACC, -cfg.D8[PIDLEVEL] * 5, +cfg.D8[PIDLEVEL] * 5);
|
||||||
|
|
||||||
|
@ -360,8 +360,8 @@ static void pidRewrite(void)
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
// -----Get the desired angle rate depending on flight mode
|
// -----Get the desired angle rate depending on flight mode
|
||||||
if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2 ) { // MODE relying on ACC
|
if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2 ) { // MODE relying on ACC
|
||||||
// calculate error and limit the angle to 50 degrees max inclination
|
// calculate error and limit the angle to max configured inclination
|
||||||
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -500, +500) - angle[axis] + cfg.angleTrim[axis]; // 16 bits is ok here
|
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int)mcfg.max_angle_inclination), +mcfg.max_angle_inclination) - angle[axis] + cfg.angleTrim[axis]; // 16 bits is ok here
|
||||||
}
|
}
|
||||||
if (axis == 2) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
if (axis == 2) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
||||||
AngleRateTmp = (((int32_t)(cfg.yawRate + 27) * rcCommand[2]) >> 5);
|
AngleRateTmp = (((int32_t)(cfg.yawRate + 27) * rcCommand[2]) >> 5);
|
||||||
|
|
1
src/mw.h
1
src/mw.h
|
@ -249,6 +249,7 @@ typedef struct master_t {
|
||||||
uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter
|
uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter
|
||||||
uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively
|
uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively
|
||||||
uint8_t moron_threshold; // 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.
|
uint8_t moron_threshold; // 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 max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
|
||||||
int16_t accZero[3];
|
int16_t accZero[3];
|
||||||
int16_t magZero[3];
|
int16_t magZero[3];
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue