1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

Added controlrateConfig parameter group

This commit is contained in:
Martin Budden 2017-01-10 23:50:29 +00:00
parent 20a4913bb0
commit 9b2750526c
20 changed files with 200 additions and 132 deletions

View file

@ -471,7 +471,6 @@ COMMON_SRC = \
build/assert.c \
$(TARGET_DIR_SRC) \
main.c \
fc/mw.c \
common/encoding.c \
common/filter.c \
common/maths.c \
@ -482,8 +481,6 @@ COMMON_SRC = \
config/config_eeprom.c \
config/config_streamer.c \
config/parameter_group.c \
fc/config.c \
fc/runtime_config.c \
drivers/logging.c \
drivers/adc.c \
drivers/buf_writer.c \
@ -516,12 +513,16 @@ COMMON_SRC = \
flight/mixer.c \
flight/servos.c \
flight/pid.c \
fc/config.c \
fc/controlrate_profile.c \
fc/fc_init.c \
fc/fc_tasks.c \
fc/fc_hardfaults.c \
fc/fc_msp.c \
fc/mw.c \
fc/rc_controls.c \
fc/rc_curves.c \
fc/runtime_config.c \
fc/serial_cli.c \
io/beeper.c \
io/serial.c \

View file

@ -53,6 +53,7 @@
#include "sensors/battery.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"

View file

@ -36,15 +36,18 @@
#include "cms/cms_menu_imu.h"
#include "common/axis.h"
#include "io/gimbal.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "flight/servos.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "io/gimbal.h"
#include "sensors/gyro.h"
#include "config/config_profile.h"
@ -295,7 +298,7 @@ static uint16_t cmsx_rateYaw;
static long cmsx_RateProfileRead(void)
{
memcpy(&rateProfile, &masterConfig.controlRateProfiles[rateProfileIndex], sizeof(controlRateConfig_t));
memcpy(&rateProfile, controlRateProfiles(rateProfileIndex), sizeof(controlRateConfig_t));
cmsx_rateRoll = DEKADEGREES_TO_DEGREES(rateProfile.rates[FD_ROLL]);
cmsx_ratePitch = DEKADEGREES_TO_DEGREES(rateProfile.rates[FD_PITCH]);
@ -312,7 +315,7 @@ static long cmsx_RateProfileWriteback(const OSD_Entry *self)
rateProfile.rates[FD_PITCH] = DEGREES_TO_DEKADEGREES(cmsx_ratePitch);
rateProfile.rates[FD_YAW] = DEGREES_TO_DEKADEGREES(cmsx_rateYaw);
memcpy(&masterConfig.controlRateProfiles[rateProfileIndex], &rateProfile, sizeof(controlRateConfig_t));
memcpy((controlRateConfig_t *)controlRateProfiles(rateProfileIndex), &rateProfile, sizeof(controlRateConfig_t));
return 0;
}
@ -329,6 +332,8 @@ static OSD_Entry cmsx_menuRateProfileEntries[] =
{
{ "-- RATE --", OME_Label, NULL, rateProfileIndexString, 0 },
//!!TODO - fix up CMS menu entries to use parameter groups
/*
#if 0
{ "RC RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t){ &rateProfile.rcRate8, 0, 255, 1, 10 }, 0 },
{ "RC YAW RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t){ &rateProfile.rcYawRate8, 0, 255, 1, 10 }, 0 },
@ -346,7 +351,7 @@ static OSD_Entry cmsx_menuRateProfileEntries[] =
{ "THRPID ATT", OME_UINT8, NULL, &(OSD_UINT8_t){ &rateProfile.dynThrPID, 0, 100, 1 }, 0 },
{ "TPA BRKPT", OME_UINT16, NULL, &(OSD_UINT16_t){ &rateProfile.tpa_breakpoint, 1000, 2000, 10}, 0 },
*/
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};

View file

@ -145,7 +145,6 @@ typedef struct master_s {
profile_t profile[MAX_PROFILE_COUNT];
uint8_t current_profile_index;
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
uint32_t beeper_off_flags;
uint32_t preferred_beeper_off_flags;
@ -162,6 +161,5 @@ typedef struct master_s {
extern master_t masterConfig;
extern profile_t *currentProfile;
extern controlRateConfig_t *currentControlRateProfile;
void createDefaultConfig(master_t *config);

View file

@ -17,6 +17,8 @@
#pragma once
#include <string.h>
#ifndef __UNIQL
# define __UNIQL_CONCAT2(x,y) x ## y
# define __UNIQL_CONCAT(x,y) __UNIQL_CONCAT2(x,y)

View file

@ -27,7 +27,7 @@
//#define PG_SENSOR_TRIMS 9 -- NOT USED in iNav
#define PG_GYRO_CONFIG 10
#define PG_BATTERY_CONFIG 11
//#define PG_CONTROL_RATE_PROFILES 12
#define PG_CONTROL_RATE_PROFILES 12
//#define PG_SERIAL_CONFIG 13
//#define PG_PID_PROFILE 14
//#define PG_GTUNE_CONFIG 15

View file

@ -45,8 +45,6 @@
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
@ -64,6 +62,9 @@
#include "flight/navigation_rewrite.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "fc/runtime_config.h"
#include "config/config_eeprom.h"
@ -84,9 +85,6 @@
master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile;
void resetPidProfile(pidProfile_t *pidProfile)
{
pidProfile->P8[ROLL] = 40;
@ -280,24 +278,6 @@ void resetSerialConfig(serialConfig_t *serialConfig)
serialConfig->reboot_character = 'R';
}
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
{
controlRateConfig->rcExpo8 = 70;
controlRateConfig->thrMid8 = 50;
controlRateConfig->thrExpo8 = 0;
controlRateConfig->dynThrPID = 0;
controlRateConfig->rcYawExpo8 = 20;
controlRateConfig->tpa_breakpoint = 1500;
for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
if (axis == FD_YAW) {
controlRateConfig->rates[axis] = CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT;
} else {
controlRateConfig->rates[axis] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT;
}
}
}
void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
{
@ -429,8 +409,6 @@ void createDefaultConfig(master_t *config)
resetPidProfile(&config->profile[0].pidProfile);
resetControlRateConfig(&config->controlRateProfiles[0]);
// for (int i = 0; i < CHECKBOXITEMS; i++)
// cfg.activate[i] = 0;
@ -558,11 +536,6 @@ void createDefaultConfig(master_t *config)
memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
}
// copy first control rate config into remaining profile
for (int i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
memcpy(&config->controlRateProfiles[i], &config->controlRateProfiles[0], sizeof(controlRateConfig_t));
}
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
config->profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT;
}
@ -582,11 +555,6 @@ void resetConfigs(void)
#endif
}
static void activateControlRateConfig(void)
{
generateThrottleCurve(currentControlRateProfile);
}
static void activateConfig(void)
{
activateControlRateConfig();
@ -926,26 +894,6 @@ void changeProfile(uint8_t profileIndex)
beeperConfirmationBeeps(profileIndex + 1);
}
uint8_t getCurrentControlRateProfile(void)
{
return currentControlRateProfileIndex;
}
void setControlRateProfile(uint8_t profileIndex)
{
currentControlRateProfileIndex = profileIndex;
currentControlRateProfile = &masterConfig.controlRateProfiles[profileIndex];
}
void changeControlRateProfile(uint8_t profileIndex)
{
if (profileIndex >= MAX_CONTROL_RATE_PROFILE_COUNT) {
profileIndex = MAX_CONTROL_RATE_PROFILE_COUNT - 1;
}
setControlRateProfile(profileIndex);
activateControlRateConfig();
}
void persistentFlagClearAll()
{
masterConfig.persistentFlags = 0;

View file

@ -21,7 +21,6 @@
#include <stdbool.h>
#define MAX_PROFILE_COUNT 3
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
#define MAX_NAME_LENGTH 16
@ -99,10 +98,6 @@ void changeProfile(uint8_t profileIndex);
struct pidProfile_s;
void resetPidProfile(struct pidProfile_s *pidProfile);
void setControlRateProfile(uint8_t profileIndex);
void changeControlRateProfile(uint8_t profileIndex);
uint8_t getCurrentControlRateProfile(void);
bool canSoftwareSerialBeUsed(void);
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch);

View file

@ -0,0 +1,78 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "common/axis.h"
#include "config/config_reset.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_curves.h"
static uint8_t currentControlRateProfileIndex = 0;
const controlRateConfig_t *currentControlRateProfile;
PG_REGISTER_ARR_WITH_RESET_FN(const controlRateConfig_t, MAX_CONTROL_RATE_PROFILE_COUNT, controlRateProfiles, PG_CONTROL_RATE_PROFILES, 0);
void pgResetFn_controlRateProfiles(const controlRateConfig_t *instance)
{
for (int i = 0; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
RESET_CONFIG(const controlRateConfig_t, ((controlRateConfig_t*)&instance[i]),
.rcExpo8 = 70,
.thrMid8 = 50,
.thrExpo8 = 0,
.dynThrPID = 0,
.rcYawExpo8 = 20,
.tpa_breakpoint = 1500,
.rates[FD_ROLL] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT,
.rates[FD_PITCH] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT,
.rates[FD_YAW] = CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT
);
}
}
uint8_t getCurrentControlRateProfile(void)
{
return currentControlRateProfileIndex;
}
void setControlRateProfile(uint8_t profileIndex)
{
currentControlRateProfileIndex = profileIndex;
currentControlRateProfile = controlRateProfiles(profileIndex);
}
void activateControlRateConfig(void)
{
generateThrottleCurve(currentControlRateProfile);
}
void changeControlRateProfile(uint8_t profileIndex)
{
if (profileIndex >= MAX_CONTROL_RATE_PROFILE_COUNT) {
profileIndex = MAX_CONTROL_RATE_PROFILE_COUNT - 1;
}
setControlRateProfile(profileIndex);
activateControlRateConfig();
}

View file

@ -0,0 +1,60 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
#include "config/parameter_group.h"
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
/*
Max and min available values for rates are now stored as absolute
tenths of degrees-per-second [dsp/10]
That means, max. rotation rate 180 equals 1800dps
New defaults of 200dps for pitch,roll and yaw are more less
equivalent of rates 0 from previous versions of iNav, Cleanflight, Baseflight
and so on.
*/
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 180
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN 6
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT 20
#define CONTROL_RATE_CONFIG_YAW_RATE_MAX 180
#define CONTROL_RATE_CONFIG_YAW_RATE_MIN 2
#define CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT 20
#define CONTROL_RATE_CONFIG_TPA_MAX 100
typedef struct controlRateConfig_s {
uint16_t tpa_breakpoint; // Breakpoint where TPA is activated
uint8_t rcExpo8;
uint8_t thrMid8;
uint8_t thrExpo8;
uint8_t rates[3];
uint8_t dynThrPID;
uint8_t rcYawExpo8;
} controlRateConfig_t;
PG_DECLARE_ARR(const controlRateConfig_t, MAX_CONTROL_RATE_PROFILE_COUNT, controlRateProfiles);
extern const controlRateConfig_t *currentControlRateProfile;
void setControlRateProfile(uint8_t profileIndex);
void changeControlRateProfile(uint8_t profileIndex);
void activateControlRateConfig(void);
uint8_t getCurrentControlRateProfile(void);

View file

@ -43,6 +43,7 @@
#include "drivers/system.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/fc_msp.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
@ -1349,23 +1350,24 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_RC_TUNING:
if (dataSize >= 10) {
sbufReadU8(src); //Read rcRate8, kept for protocol compatibility reasons
currentControlRateProfile->rcExpo8 = sbufReadU8(src);
// need to cast away const to set controlRateProfile
((controlRateConfig_t*)currentControlRateProfile)->rcExpo8 = sbufReadU8(src);
for (int i = 0; i < 3; i++) {
rate = sbufReadU8(src);
if (i == FD_YAW) {
currentControlRateProfile->rates[i] = constrain(rate, CONTROL_RATE_CONFIG_YAW_RATE_MIN, CONTROL_RATE_CONFIG_YAW_RATE_MAX);
((controlRateConfig_t*)currentControlRateProfile)->rates[i] = constrain(rate, CONTROL_RATE_CONFIG_YAW_RATE_MIN, CONTROL_RATE_CONFIG_YAW_RATE_MAX);
}
else {
currentControlRateProfile->rates[i] = constrain(rate, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
((controlRateConfig_t*)currentControlRateProfile)->rates[i] = constrain(rate, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
}
}
rate = sbufReadU8(src);
currentControlRateProfile->dynThrPID = MIN(rate, CONTROL_RATE_CONFIG_TPA_MAX);
currentControlRateProfile->thrMid8 = sbufReadU8(src);
currentControlRateProfile->thrExpo8 = sbufReadU8(src);
currentControlRateProfile->tpa_breakpoint = sbufReadU16(src);
((controlRateConfig_t*)currentControlRateProfile)->dynThrPID = MIN(rate, CONTROL_RATE_CONFIG_TPA_MAX);
((controlRateConfig_t*)currentControlRateProfile)->thrMid8 = sbufReadU8(src);
((controlRateConfig_t*)currentControlRateProfile)->thrExpo8 = sbufReadU8(src);
((controlRateConfig_t*)currentControlRateProfile)->tpa_breakpoint = sbufReadU16(src);
if (dataSize >= 11) {
currentControlRateProfile->rcYawExpo8 = sbufReadU8(src);
((controlRateConfig_t*)currentControlRateProfile)->rcYawExpo8 = sbufReadU8(src);
}
schedulePidGainsUpdate();

View file

@ -46,6 +46,7 @@
#include "sensors/battery.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "fc/runtime_config.h"

View file

@ -34,6 +34,7 @@
#include "drivers/system.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/mw.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
@ -502,7 +503,7 @@ void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adj
MARK_ADJUSTMENT_FUNCTION_AS_READY(index);
}
void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta) {
static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta) {
int newValue;
if (delta > 0) {
@ -638,7 +639,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
#define RESET_FREQUENCY_2HZ (1000 / 2)
void processRcAdjustments(controlRateConfig_t *controlRateConfig)
void processRcAdjustments(const controlRateConfig_t *controlRateConfig)
{
uint8_t adjustmentIndex;
uint32_t now = millis();
@ -687,7 +688,8 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig)
continue;
}
applyStepAdjustment(controlRateConfig, adjustmentFunction, delta);
// it is legitimate to adjust an otherwise const item here
applyStepAdjustment((controlRateConfig_t*)controlRateConfig, adjustmentFunction, delta);
} else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) {
uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;

View file

@ -103,23 +103,6 @@ typedef enum {
#define MIN_MODE_RANGE_STEP 0
#define MAX_MODE_RANGE_STEP ((CHANNEL_RANGE_MAX - CHANNEL_RANGE_MIN) / 25)
/*
Max and min available values for rates are now stored as absolute
tenths of degrees-per-second [dsp/10]
That means, max. rotation rate 180 equals 1800dps
New defaults of 200dps for pitch,roll and yaw are more less
equivalent of rates 0 from previous versions of iNav, Cleanflight, Baseflight
and so on.
*/
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 180
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN 6
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT 20
#define CONTROL_RATE_CONFIG_YAW_RATE_MAX 180
#define CONTROL_RATE_CONFIG_YAW_RATE_MIN 2
#define CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT 20
#define CONTROL_RATE_CONFIG_TPA_MAX 100
// steps are 25 apart
// a value of 0 corresponds to a channel value of 900 or less
@ -143,16 +126,6 @@ typedef enum {
MODE_OPERATOR_AND
} modeActivationOperator_e;
typedef struct controlRateConfig_s {
uint8_t rcExpo8;
uint8_t thrMid8;
uint8_t thrExpo8;
uint8_t rates[3];
uint8_t dynThrPID;
uint8_t rcYawExpo8;
uint16_t tpa_breakpoint; // Breakpoint where TPA is activated
} controlRateConfig_t;
extern int16_t rcCommand[4];
typedef struct rcControlsConfig_s {
@ -260,7 +233,8 @@ typedef struct adjustmentState_s {
void resetAdjustmentStates(void);
void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig);
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
void processRcAdjustments(controlRateConfig_t *controlRateConfig);
struct controlRateConfig_s;
void processRcAdjustments(const struct controlRateConfig_s *controlRateConfig);
bool isUsingSticksForArming(void);
bool isUsingNavigationModes(void);

View file

@ -20,12 +20,14 @@
#include "platform.h"
#include "rx/rx.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "flight/mixer.h"
#include "rx/rx.h"
#define PITCH_LOOKUP_LENGTH 7
#define YAW_LOOKUP_LENGTH 7
@ -34,7 +36,7 @@
static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
int16_t lookupThrottleRCMid; // THROTTLE curve mid point
void generateThrottleCurve(controlRateConfig_t *controlRateConfig)
void generateThrottleCurve(const controlRateConfig_t *controlRateConfig)
{
lookupThrottleRCMid = motorConfig()->minthrottle + (int32_t)(motorConfig()->maxthrottle - motorConfig()->minthrottle) * controlRateConfig->thrMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE]

View file

@ -18,7 +18,7 @@
#pragma once
struct controlRateConfig_s;
void generateThrottleCurve(struct controlRateConfig_s *controlRateConfig);
void generateThrottleCurve(const struct controlRateConfig_s *controlRateConfig);
int16_t rcLookup(int32_t stickDeflection, uint8_t expo);
int16_t rcLookupThrottle(int32_t tmp);

View file

@ -66,6 +66,7 @@ uint8_t cliMode = 0;
#include "drivers/timer.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "fc/serial_cli.h"
@ -623,6 +624,21 @@ static const clivalue_t valueTable[] = {
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_SERVO_CONFIG, offsetof(servoConfig_t, servoCenterPulse) },
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 50, 498 }, PG_SERVO_CONFIG, offsetof(servoConfig_t, servoPwmRate) },
#endif
// PG_CONTROLRATE_PROFILE
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo8) },
{ "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawExpo8) },
{ "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrMid8) },
{ "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrExpo8) },
// New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
// Rate 180 (1800dps) is max. value gyro can measure reliably
{ "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_ROLL]) },
{ "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_PITCH]) },
{ "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { CONTROL_RATE_CONFIG_YAW_RATE_MIN, CONTROL_RATE_CONFIG_YAW_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_YAW]) },
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX}, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, dynThrPID) },
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX}, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, tpa_breakpoint) },
};
#else
@ -783,22 +799,6 @@ const clivalue_t valueTable[] = {
{ "mode_range_logic_operator", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.modeActivationOperator, .config.lookup = { TABLE_AUX_OPERATOR } },
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 } },
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, .config.minmax = { 0, 100 } },
{ "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcYawExpo8, .config.minmax = { 0, 100 } },
{ "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, .config.minmax = { 0, 100 } },
{ "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, .config.minmax = { 0, 100 } },
/*
New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
Rate 180 (1800dps) is max. value gyro can measure reliably
*/
{ "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_ROLL], .config.minmax = { CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, },
{ "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_PITCH], .config.minmax = { CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, },
{ "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_YAW], .config.minmax = { CONTROL_RATE_CONFIG_YAW_RATE_MIN, CONTROL_RATE_CONFIG_YAW_RATE_MAX }, },
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX}, },
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX}, },
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 }, },
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 }, },

View file

@ -42,6 +42,7 @@
#include "flight/navigation_rewrite_private.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/runtime_config.h"
// If we are going slower than NAV_FW_MIN_VEL_SPEED_BOOST - boost throttle to fight against the wind
@ -55,10 +56,6 @@ static bool isPitchAdjustmentValid = false;
static bool isRollAdjustmentValid = false;
static float throttleSpeedAdjustment = 0;
/*-----------------------------------------------------------
* Backdoor to MW
*-----------------------------------------------------------*/
extern controlRateConfig_t *currentControlRateProfile;
/*-----------------------------------------------------------
* Altitude controller

View file

@ -31,6 +31,7 @@
#include "config/config_master.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"

View file

@ -38,6 +38,7 @@
#include "common/typeconversion.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/runtime_config.h"
#include "fc/rc_controls.h"