Merge pull request #1687 from martinbudden/bf_accelerometer_to_structs

Moved masterConfig accelerometer items to struct. masterConfig tidy.
This commit is contained in:
Martin Budden 2016-11-29 22:24:19 +01:00 committed by GitHub
commit c0761eb619
9 changed files with 64 additions and 62 deletions

View File

@ -1269,7 +1269,7 @@ static bool blackboxWriteSysinfo()
masterConfig.gyroConfig.gyro_soft_notch_hz_2);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", masterConfig.gyroConfig.gyro_soft_notch_cutoff_1,
masterConfig.gyroConfig.gyro_soft_notch_cutoff_2);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.accelerometerConfig.acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.sensorSelectionConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.sensorSelectionConfig.baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.sensorSelectionConfig.mag_hardware);

View File

@ -87,13 +87,15 @@ typedef struct master_s {
// global sensor-related stuff
sensorSelectionConfig_t sensorSelectionConfig;
sensorAlignmentConfig_t sensorAlignmentConfig;
sensorTrims_t sensorTrims;
boardAlignment_t boardAlignment;
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
accDeadband_t accDeadband;
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
@ -102,12 +104,9 @@ typedef struct master_s {
gyroConfig_t gyroConfig;
compassConfig_t compassConfig;
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
accelerometerConfig_t accelerometerConfig;
uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
accDeadband_t accDeadband;
barometerConfig_t barometerConfig;
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
throttleCorrectionConfig_t throttleCorrectionConfig;
@ -121,9 +120,6 @@ typedef struct master_s {
gpsConfig_t gpsConfig;
#endif
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
sensorTrims_t sensorTrims;
rxConfig_t rxConfig;
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.

View File

@ -30,54 +30,54 @@
#define PG_CONTROL_RATE_PROFILES 12 // struct OK, needs to be split out of rc_controls.h into rate_profile.h
#define PG_SERIAL_CONFIG 13 // struct OK
#define PG_PID_PROFILE 14 // struct OK, CF differences
#define PG_GTUNE_CONFIG 15
#define PG_ARMING_CONFIG 16
#define PG_TRANSPONDER_CONFIG 17
#define PG_SYSTEM_CONFIG 18
#define PG_FEATURE_CONFIG 19
#define PG_MIXER_CONFIG 20
#define PG_SERVO_MIXER 21
#define PG_IMU_CONFIG 22
#define PG_PROFILE_SELECTION 23
#define PG_RX_CONFIG 24
#define PG_RC_CONTROLS_CONFIG 25
#define PG_MOTOR_3D_CONFIG 26
#define PG_LED_STRIP_CONFIG 27
#define PG_COLOR_CONFIG 28
#define PG_AIRPLANE_ALT_HOLD_CONFIG 29
#define PG_GPS_CONFIG 30
#define PG_TELEMETRY_CONFIG 31
#define PG_FRSKY_TELEMETRY_CONFIG 32
#define PG_HOTT_TELEMETRY_CONFIG 33
#define PG_NAVIGATION_CONFIG 34
#define PG_ACCELEROMETER_CONFIG 35
#define PG_RATE_PROFILE_SELECTION 36
#define PG_ADJUSTMENT_PROFILE 37
#define PG_BAROMETER_CONFIG 38
#define PG_GTUNE_CONFIG 15 // is GTUNE still being used?
#define PG_ARMING_CONFIG 16 // structs OK, CF naming differences
#define PG_TRANSPONDER_CONFIG 17 // struct OK
#define PG_SYSTEM_CONFIG 18 // just has i2c_highspeed
#define PG_FEATURE_CONFIG 19 // just has enabledFeatures
#define PG_MIXER_CONFIG 20 // Cleanflight has single struct mixerConfig_t, betaflight has mixerConfig_t and servoMixerConfig_t
#define PG_SERVO_MIXER 21 // Cleanflight has servoParam_t for each servo, betaflight has single servoParam_t
#define PG_IMU_CONFIG 22 // Cleanflight has imuConfig_t, betaflight has imuRuntimeConfig_t with additional parameters
#define PG_PROFILE_SELECTION 23 // just contains current_profile_index
#define PG_RX_CONFIG 24 // betaflight rxConfig_t contains different values
#define PG_RC_CONTROLS_CONFIG 25 // Cleanflight has more parameters in rcControlsConfig_t
#define PG_MOTOR_3D_CONFIG 26 // Cleanflight has motor3DConfig_t, betaflight has flight3DConfig_t with more parameters
#define PG_LED_STRIP_CONFIG 27 // structs OK
#define PG_COLOR_CONFIG 28 // part of led strip, structs OK
#define PG_AIRPLANE_ALT_HOLD_CONFIG 29 // struct OK
#define PG_GPS_CONFIG 30 // struct OK
#define PG_TELEMETRY_CONFIG 31 // betaflight has more and different data in telemetryConfig_t
#define PG_FRSKY_TELEMETRY_CONFIG 32 // Cleanflight has split data out of PG_TELEMETRY_CONFIG
#define PG_HOTT_TELEMETRY_CONFIG 33 // Cleanflight has split data out of PG_TELEMETRY_CONFIG
#define PG_NAVIGATION_CONFIG 34 // structs OK
#define PG_ACCELEROMETER_CONFIG 35 // no accelerometerConfig_t in betaflight
#define PG_RATE_PROFILE_SELECTION 36 // part of profile in betaflight
#define PG_ADJUSTMENT_PROFILE 37 // array needs to be made into struct
#define PG_BAROMETER_CONFIG 38 // structs OK
#define PG_THROTTLE_CORRECTION_CONFIG 39
#define PG_COMPASS_CONFIGURATION 40
#define PG_MODE_ACTIVATION_PROFILE 41
#define PG_COMPASS_CONFIGURATION 40 // structs OK
#define PG_MODE_ACTIVATION_PROFILE 41 // array needs to be made into struct
#define PG_SERVO_PROFILE 42
#define PG_FAILSAFE_CHANNEL_CONFIG 43
#define PG_CHANNEL_RANGE_CONFIG 44
#define PG_MODE_COLOR_CONFIG 45
#define PG_SPECIAL_COLOR_CONFIG 46
#define PG_PILOT_CONFIG 47
#define PG_MSP_SERVER_CONFIG 48
#define PG_VOLTAGE_METER_CONFIG 49
#define PG_AMPERAGE_METER_CONFIG 50
#define PG_FAILSAFE_CHANNEL_CONFIG 43 // structs OK
#define PG_CHANNEL_RANGE_CONFIG 44 // structs OK
#define PG_MODE_COLOR_CONFIG 45 // part of led strip, structs OK
#define PG_SPECIAL_COLOR_CONFIG 46 // part of led strip, structs OK
#define PG_PILOT_CONFIG 47 // does not exist in betaflight
#define PG_MSP_SERVER_CONFIG 48 // does not exist in betaflight
#define PG_VOLTAGE_METER_CONFIG 49 // Cleanflight has voltageMeterConfig_t, betaflight has batteryConfig_t
#define PG_AMPERAGE_METER_CONFIG 50 // Cleanflight has amperageMeterConfig_t, betaflight has batteryConfig_t
// Driver configuration
#define PG_DRIVER_PWM_RX_CONFIG 100
#define PG_DRIVER_FLASHCHIP_CONFIG 101
#define PG_DRIVER_PWM_RX_CONFIG 100 // does not exist in betaflight
#define PG_DRIVER_FLASHCHIP_CONFIG 101 // does not exist in betaflight
// OSD configuration (subject to change)
#define PG_OSD_FONT_CONFIG 32768
#define PG_OSD_VIDEO_CONFIG 32769
#define PG_OSD_ELEMENT_CONFIG 32770
#define PG_OSD_FONT_CONFIG 2047
#define PG_OSD_VIDEO_CONFIG 2046
#define PG_OSD_ELEMENT_CONFIG 2045
#define PG_RESERVED_FOR_TESTING_1 65533
#define PG_RESERVED_FOR_TESTING_2 65534
#define PG_RESERVED_FOR_TESTING_3 65535
// 4095 is currently the highest number that can be used for a PGN due to the top 4 bits of the 16 bit value being reserved for the version when the PG is stored in an EEPROM.
#define PG_RESERVED_FOR_TESTING_1 4095
#define PG_RESERVED_FOR_TESTING_2 4094
#define PG_RESERVED_FOR_TESTING_3 4093

View File

@ -596,7 +596,7 @@ void createDefaultConfig(master_t *config)
config->boardAlignment.yawDegrees = 0;
config->sensorSelectionConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
config->max_angle_inclination = 700; // 70 degrees
config->yaw_control_direction = 1;
config->rcControlsConfig.yaw_control_direction = 1;
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
// xxx_hardware: 0:default/autodetect, 1: disable
@ -701,7 +701,8 @@ void createDefaultConfig(master_t *config)
resetRollAndPitchTrims(&config->accelerometerTrims);
config->compassConfig.mag_declination = 0;
config->acc_lpf_hz = 10.0f;
config->accelerometerConfig.acc_lpf_hz = 10.0f;
config->accDeadband.xy = 40;
config->accDeadband.z = 40;
config->acc_unarmedcal = 1;
@ -844,7 +845,7 @@ void activateConfig(void)
useFailsafeConfig(&masterConfig.failsafeConfig);
setAccelerationTrims(&masterConfig.sensorTrims.accZero);
setAccelerationFilter(masterConfig.acc_lpf_hz);
setAccelerationFilter(masterConfig.accelerometerConfig.acc_lpf_hz);
mixerUseConfigs(
&masterConfig.flight3DConfig,

View File

@ -296,7 +296,7 @@ void updateRcCommands(void)
} else {
tmp = 0;
}
rcCommand[axis] = tmp * -masterConfig.yaw_control_direction;
rcCommand[axis] = tmp * -masterConfig.rcControlsConfig.yaw_control_direction;
}
if (rcData[axis] < masterConfig.rxConfig.midrc) {
rcCommand[axis] = -rcCommand[axis];
@ -484,7 +484,7 @@ void updateMagHold(void)
dif += 360;
if (dif >= +180)
dif -= 360;
dif *= -masterConfig.yaw_control_direction;
dif *= -masterConfig.rcControlsConfig.yaw_control_direction;
if (STATE(SMALL_ANGLE))
rcCommand[YAW] -= dif * currentProfile->pidProfile.P8[PIDMAG] / 30; // 18 deg
} else

View File

@ -162,6 +162,7 @@ typedef struct rcControlsConfig_s {
uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero.
uint8_t alt_hold_deadband; // defines the neutral zone of throttle stick during altitude hold, default setting is +/-40
uint8_t alt_hold_fast_change; // when disabled, turn off the althold when throttle stick is out of deadband defined with alt_hold_deadband; when enabled, altitude changes slowly proportional to stick movement
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
} rcControlsConfig_t;
typedef struct armingConfig_s {

View File

@ -57,7 +57,6 @@ typedef struct throttleCorrectionConfig_s {
} throttleCorrectionConfig_t;
typedef struct imuRuntimeConfig_s {
uint8_t acc_cut_hz;
uint8_t acc_unarmedcal;
float dcm_ki;
float dcm_kp;

View File

@ -831,7 +831,7 @@ const clivalue_t valueTable[] = {
{ "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttleCorrectionConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
{ "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttleCorrectionConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
@ -869,7 +869,7 @@ const clivalue_t valueTable[] = {
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorSelectionConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
{ "acc_lpf_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
{ "acc_lpf_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.accelerometerConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
{ "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
{ "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
{ "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },

View File

@ -52,6 +52,11 @@ typedef union rollAndPitchTrims_u {
rollAndPitchTrims_t_def values;
} rollAndPitchTrims_t;
typedef struct accelerometerConfig_s {
uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
} accelerometerConfig_t;
void accInit(uint32_t gyroTargetLooptime);
bool isAccelerationCalibrationComplete(void);
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);