1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00

Rename freq parameter; remove UT warnings

This commit is contained in:
Joel Fuster 2015-01-04 22:15:09 -05:00
parent dc3271255c
commit 06ce23951b
5 changed files with 12 additions and 8 deletions

View file

@ -428,7 +428,7 @@ static void resetConf(void)
currentProfile->mixerConfig.yaw_direction = 1;
currentProfile->mixerConfig.tri_unarmed_servo = 1;
currentProfile->mixerConfig.servo_lowpass_freq_idx = 99;
currentProfile->mixerConfig.servo_lowpass_freq = 400;
currentProfile->mixerConfig.servo_lowpass_enable = 0;
// gimbal

View file

@ -58,14 +58,16 @@
#include "drivers/system.h"
extern int16_t debug[4];
#ifndef UNIT_TEST
static uint8_t motorCount = 0;
static int useServo;
static uint8_t servoCount;
#endif
int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
int16_t servo[MAX_SUPPORTED_SERVOS];
static int useServo;
static uint8_t servoCount;
static servoParam_t *servoConf;
static mixerConfig_t *mixerConfig;
@ -75,8 +77,10 @@ static airplaneConfig_t *airplaneConfig;
static rxConfig_t *rxConfig;
static gimbalConfig_t *gimbalConfig;
#ifndef UNIT_TEST
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
static mixerMode_e currentMixerMode;
#endif
static lowpass_t lowpassFilters[MAX_SUPPORTED_SERVOS];
static const motorMixer_t mixerQuadX[] = {
@ -775,7 +779,7 @@ void filterServos(void)
if (mixerConfig->servo_lowpass_enable) {
for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) {
servo[servoIdx] = (int16_t)lowpass_fixed(&lowpassFilters[servoIdx], (float)servo[servoIdx], mixerConfig->servo_lowpass_freq_idx);
servo[servoIdx] = (int16_t)lowpass_fixed(&lowpassFilters[servoIdx], (float)servo[servoIdx], mixerConfig->servo_lowpass_freq);
// Sanity check
servo[servoIdx] = constrain(servo[servoIdx], servoConf[servoIdx].min, servoConf[servoIdx].max);

View file

@ -66,7 +66,7 @@ typedef struct mixer_t {
typedef struct mixerConfig_s {
int8_t yaw_direction;
uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed
int16_t servo_lowpass_freq_idx; // lowpass servo filter frequency selection
int16_t servo_lowpass_freq; // lowpass servo filter frequency selection; 1/1000ths of loop freq
int8_t servo_lowpass_enable; // enable/disable lowpass filter
} mixerConfig_t;

View file

@ -332,7 +332,7 @@ const clivalue_t valueTable[] = {
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, -1, 1 },
{ "yaw_direction", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.yaw_direction, -1, 1 },
{ "tri_unarmed_servo", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.tri_unarmed_servo, 0, 1 },
{ "servo_lowpass_freq_idx", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.servo_lowpass_freq_idx, 0, 99},
{ "servo_lowpass_freq", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.servo_lowpass_freq, 10, 400},
{ "servo_lowpass_enable", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.servo_lowpass_enable, 0, 1 },
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 },

View file

@ -127,7 +127,7 @@ TEST(MixerTest, ServoLowpassFilter)
printf("*** Testing freq: %d (%f)\n", freq, ((float)freq * 0.001f));
mixerConfig.servo_lowpass_enable = 1;
mixerConfig.servo_lowpass_freq_idx = freq;
mixerConfig.servo_lowpass_freq = freq;
mixerUseConfigs(servoConfig, NULL, NULL, &mixerConfig, NULL, NULL, NULL);
// Run tests