Removed dependency of pwm_output driver on mixers and servos

This commit is contained in:
Martin Budden 2017-02-17 13:42:33 +00:00
parent 367f62236a
commit 781b1b1352
22 changed files with 103 additions and 93 deletions

View File

@ -1292,9 +1292,9 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", rxConfig()->rcInterpolationInterval);
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", rxConfig()->airModeActivateThreshold);
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider:%d", rxConfig()->serialrx_provider);
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", motorConfig()->useUnsyncedPwm);
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", motorConfig()->motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", motorConfig()->motorPwmRate);
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", motorConfig()->dev.useUnsyncedPwm);
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", motorConfig()->dev.motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", motorConfig()->dev.motorPwmRate);
BLACKBOX_PRINT_HEADER_LINE("digitalIdleOffset:%d", (int)(motorConfig()->digitalIdleOffsetPercent * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("debug_mode:%d", systemConfig()->debug_mode);
BLACKBOX_PRINT_HEADER_LINE("features:%d", featureConfig()->enabledFeatures);

View File

@ -23,11 +23,8 @@
#include "platform.h"
#include "io.h"
#include "timer.h"
#include "pwm_output.h"
#include "flight/mixer.h" //!!TODO remove dependency on this
#include "flight/servos.h" //!!TODO remove dependency on this
#include "timer.h"
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
@ -197,7 +194,7 @@ void pwmCompleteMotorUpdate(uint8_t motorCount)
pwmCompleteWritePtr(motorCount);
}
void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount)
void motorInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount)
{
memset(motors, 0, sizeof(motors));
@ -328,7 +325,7 @@ void pwmWriteServo(uint8_t index, uint16_t value)
}
}
void servoInit(const servoConfig_t *servoConfig)
void servoInit(const servoDevConfig_t *servoConfig)
{
for (uint8_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
const ioTag_t tag = servoConfig->ioTags[servoIndex];

View File

@ -17,8 +17,17 @@
#pragma once
#include "drivers/timer.h"
#include "drivers/dma.h"
#include "dma.h"
#include "io_types.h"
#include "timer.h"
#define MAX_SUPPORTED_MOTORS 12
#if defined(USE_QUAD_MIXER_ONLY)
#define MAX_SUPPORTED_SERVOS 1
#else
#define MAX_SUPPORTED_SERVOS 8
#endif
typedef enum {
PWM_TYPE_STANDARD = 0,
@ -109,10 +118,24 @@ typedef struct {
IO_t io;
} pwmOutputPort_t;
struct motorConfig_s;
void motorInit(const struct motorConfig_s *motorConfig, uint16_t idlePulse, uint8_t motorCount);
struct servoConfig_s;
void servoInit(const struct servoConfig_s *servoConfig);
typedef struct motorDevConfig_s {
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
uint8_t motorPwmProtocol; // Pwm Protocol
uint8_t motorPwmInversion; // Active-High vs Active-Low. Useful for brushed FCs converted for brushless operation
uint8_t useUnsyncedPwm;
ioTag_t ioTags[MAX_SUPPORTED_MOTORS];
} motorDevConfig_t;
void motorInit(const motorDevConfig_t *motorDevConfig, uint16_t idlePulse, uint8_t motorCount);
typedef struct servoDevConfig_s {
// PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
uint16_t servoPwmRate; // The update rate of servo outputs (50-498Hz)
ioTag_t ioTags[MAX_SUPPORTED_SERVOS];
} servoDevConfig_t;
void servoInit(const servoDevConfig_t *servoDevConfig);
void pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);

View File

@ -32,8 +32,6 @@
#include "system.h"
#include "rcc.h"
#include "flight/mixer.h" //!!TODO remove dependency on this
static uint8_t dmaMotorTimerCount = 0;
static motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
static motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];

View File

@ -31,8 +31,6 @@
#include "system.h"
#include "rcc.h"
#include "flight/mixer.h" //!!TODO remove dependency on this
static uint8_t dmaMotorTimerCount = 0;
static motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
static motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];

View File

@ -30,8 +30,6 @@
#include "system.h"
#include "rcc.h"
#include "flight/mixer.h" //!!TODO remove dependency on this
static uint8_t dmaMotorTimerCount = 0;
static motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
static motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];

View File

@ -535,10 +535,10 @@ static const clivalue_t valueTable[] = {
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &motorConfig()->useUnsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &motorConfig()->motorPwmProtocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &motorConfig()->motorPwmRate, .config.minmax = { 200, 32000 } },
{ "motor_pwm_inversion", VAR_UINT8 | MASTER_VALUE, &motorConfig()->motorPwmInversion, .config.lookup = { TABLE_OFF_ON } },
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &motorConfig()->dev.useUnsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &motorConfig()->dev.motorPwmProtocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &motorConfig()->dev.motorPwmRate, .config.minmax = { 200, 32000 } },
{ "motor_pwm_inversion", VAR_UINT8 | MASTER_VALUE, &motorConfig()->dev.motorPwmInversion, .config.lookup = { TABLE_OFF_ON } },
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &armingConfig()->disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
{ "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &armingConfig()->gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
@ -658,10 +658,10 @@ static const clivalue_t valueTable[] = {
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
{ "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidSumLimit, .config.minmax = { 0.1, 1.0 } },
#ifdef USE_SERVOS
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->dev.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
{ "servo_lowpass_hz", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servo_lowpass_freq, .config.minmax = { 0, 400} },
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoPwmRate, .config.minmax = { 50, 498 } },
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &servoConfig()->dev.servoPwmRate, .config.minmax = { 50, 498 } },
{ "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gimbalConfig()->mode, .config.lookup = { TABLE_GIMBAL_MODE } },
{ "channel_forwarding_start", VAR_UINT8 | MASTER_VALUE, &channelForwardingConfig()->startChannel, .config.minmax = { AUX1, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
#endif
@ -3694,9 +3694,9 @@ const cliResourceValue_t resourceTable[] = {
#ifdef BEEPER
{ OWNER_BEEPER, &beeperDevConfig()->ioTag, 0 },
#endif
{ OWNER_MOTOR, &motorConfig()->ioTags[0], MAX_SUPPORTED_MOTORS },
{ OWNER_MOTOR, &motorConfig()->dev.ioTags[0], MAX_SUPPORTED_MOTORS },
#ifdef USE_SERVOS
{ OWNER_SERVO, &servoConfig()->ioTags[0], MAX_SUPPORTED_SERVOS },
{ OWNER_SERVO, &servoConfig()->dev.ioTags[0], MAX_SUPPORTED_SERVOS },
#endif
#if defined(USE_PWM) || defined(USE_PPM)
{ OWNER_PPMINPUT, &ppmConfig()->ioTag, 0 },

View File

@ -241,15 +241,15 @@ void resetLedStripConfig(ledStripConfig_t *ledStripConfig)
#ifdef USE_SERVOS
void resetServoConfig(servoConfig_t *servoConfig)
{
servoConfig->servoCenterPulse = 1500;
servoConfig->servoPwmRate = 50;
servoConfig->dev.servoCenterPulse = 1500;
servoConfig->dev.servoPwmRate = 50;
servoConfig->tri_unarmed_servo = 1;
servoConfig->servo_lowpass_freq = 0;
int servoIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && servoIndex < MAX_SUPPORTED_SERVOS; i++) {
if (timerHardware[i].usageFlags & TIM_USE_SERVO) {
servoConfig->ioTags[servoIndex] = timerHardware[i].tag;
servoConfig->dev.ioTags[servoIndex] = timerHardware[i].tag;
servoIndex++;
}
}
@ -260,22 +260,22 @@ void resetMotorConfig(motorConfig_t *motorConfig)
{
#ifdef BRUSHED_MOTORS
motorConfig->minthrottle = 1000;
motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
motorConfig->useUnsyncedPwm = true;
motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED;
motorConfig->dev.useUnsyncedPwm = true;
#else
#ifdef BRUSHED_ESC_AUTODETECT
if (hardwareMotorType == MOTOR_BRUSHED) {
motorConfig->minthrottle = 1000;
motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
motorConfig->useUnsyncedPwm = true;
motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED;
motorConfig->dev.useUnsyncedPwm = true;
} else
#endif
{
motorConfig->minthrottle = 1070;
motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
motorConfig->motorPwmProtocol = PWM_TYPE_ONESHOT125;
motorConfig->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
motorConfig->dev.motorPwmProtocol = PWM_TYPE_ONESHOT125;
}
#endif
motorConfig->maxthrottle = 2000;
@ -285,7 +285,7 @@ void resetMotorConfig(motorConfig_t *motorConfig)
int motorIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) {
if (timerHardware[i].usageFlags & TIM_USE_MOTOR) {
motorConfig->ioTags[motorIndex] = timerHardware[i].tag;
motorConfig->dev.ioTags[motorIndex] = timerHardware[i].tag;
motorIndex++;
}
}
@ -906,12 +906,12 @@ void activateConfig(void)
void validateAndFixConfig(void)
{
if((motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
if((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
motorConfigMutable()->mincommand = 1000;
}
if ((motorConfig()->motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
motorConfigMutable()->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
}
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
@ -1060,7 +1060,7 @@ void validateAndFixGyroConfig(void)
// check for looptime restrictions based on motor protocol. Motor times have safety margin
const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
float motorUpdateRestriction;
switch(motorConfig()->motorPwmProtocol) {
switch(motorConfig()->dev.motorPwmProtocol) {
case (PWM_TYPE_STANDARD):
motorUpdateRestriction = 1.0f/BRUSHLESS_MOTORS_PWM_RATE;
break;
@ -1088,11 +1088,11 @@ void validateAndFixGyroConfig(void)
}
// Prevent overriding the max rate of motors
if (motorConfig()->useUnsyncedPwm && (motorConfig()->motorPwmProtocol <= PWM_TYPE_BRUSHED) && motorConfig()->motorPwmProtocol != PWM_TYPE_STANDARD) {
if (motorConfig()->dev.useUnsyncedPwm && (motorConfig()->dev.motorPwmProtocol <= PWM_TYPE_BRUSHED) && motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD) {
uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
if(motorConfig()->motorPwmRate > maxEscRate)
motorConfigMutable()->motorPwmRate = maxEscRate;
if(motorConfig()->dev.motorPwmRate > maxEscRate)
motorConfigMutable()->dev.motorPwmRate = maxEscRate;
}
}

View File

@ -282,25 +282,25 @@ void init(void)
idlePulse = flight3DConfig()->neutral3d;
}
if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) {
if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
featureClear(FEATURE_3D);
idlePulse = 0; // brushed motors
}
mixerConfigureOutput();
motorInit(motorConfig(), idlePulse, getMotorCount());
motorInit(&motorConfig()->dev, idlePulse, getMotorCount());
#ifdef USE_SERVOS
servoConfigureOutput();
if (isMixerUsingServos()) {
//pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
servoInit(servoConfig());
servoInit(&servoConfig()->dev);
}
#endif
#if defined(USE_PWM) || defined(USE_PPM)
if (feature(FEATURE_RX_PPM)) {
ppmRxInit(ppmConfig(), motorConfig()->motorPwmProtocol);
ppmRxInit(ppmConfig(), motorConfig()->dev.motorPwmProtocol);
} else if (feature(FEATURE_RX_PARALLEL_PWM)) {
pwmRxInit(pwmConfig());
}

View File

@ -1124,14 +1124,14 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, gyroConfig()->gyro_sync_denom);
sbufWriteU8(dst, pidConfig()->pid_process_denom);
}
sbufWriteU8(dst, motorConfig()->useUnsyncedPwm);
sbufWriteU8(dst, motorConfig()->motorPwmProtocol);
sbufWriteU16(dst, motorConfig()->motorPwmRate);
sbufWriteU8(dst, motorConfig()->dev.useUnsyncedPwm);
sbufWriteU8(dst, motorConfig()->dev.motorPwmProtocol);
sbufWriteU16(dst, motorConfig()->dev.motorPwmRate);
sbufWriteU16(dst, (uint16_t)lrintf(motorConfig()->digitalIdleOffsetPercent * 100));
sbufWriteU8(dst, gyroConfig()->gyro_use_32khz);
//!!TODO gyro_isr_update to be added pending decision
//sbufWriteU8(dst, gyroConfig()->gyro_isr_update);
sbufWriteU8(dst, motorConfig()->motorPwmInversion);
sbufWriteU8(dst, motorConfig()->dev.motorPwmInversion);
break;
case MSP_FILTER_CONFIG :
@ -1491,13 +1491,13 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_ADVANCED_CONFIG:
gyroConfigMutable()->gyro_sync_denom = sbufReadU8(src);
pidConfigMutable()->pid_process_denom = sbufReadU8(src);
motorConfigMutable()->useUnsyncedPwm = sbufReadU8(src);
motorConfigMutable()->dev.useUnsyncedPwm = sbufReadU8(src);
#ifdef USE_DSHOT
motorConfigMutable()->motorPwmProtocol = constrain(sbufReadU8(src), 0, PWM_TYPE_MAX - 1);
motorConfigMutable()->dev.motorPwmProtocol = constrain(sbufReadU8(src), 0, PWM_TYPE_MAX - 1);
#else
motorConfigMutable()->motorPwmProtocol = constrain(sbufReadU8(src), 0, PWM_TYPE_BRUSHED);
motorConfigMutable()->dev.motorPwmProtocol = constrain(sbufReadU8(src), 0, PWM_TYPE_BRUSHED);
#endif
motorConfigMutable()->motorPwmRate = sbufReadU16(src);
motorConfigMutable()->dev.motorPwmRate = sbufReadU16(src);
if (sbufBytesRemaining(src) >= 2) {
motorConfigMutable()->digitalIdleOffsetPercent = sbufReadU16(src) / 100.0f;
}
@ -1511,7 +1511,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
validateAndFixGyroConfig();
if (sbufBytesRemaining(src)) {
motorConfigMutable()->motorPwmInversion = sbufReadU8(src);
motorConfigMutable()->dev.motorPwmInversion = sbufReadU8(src);
}
break;

View File

@ -248,7 +248,7 @@ float getMotorMixRange()
bool isMotorProtocolDshot(void) {
#ifdef USE_DSHOT
switch(motorConfig()->motorPwmProtocol) {
switch(motorConfig()->dev.motorPwmProtocol) {
case PWM_TYPE_DSHOT1200:
case PWM_TYPE_DSHOT600:
case PWM_TYPE_DSHOT300:

View File

@ -19,8 +19,7 @@
#include "config/parameter_group.h"
#include "drivers/io_types.h"
#define MAX_SUPPORTED_MOTORS 12
#include "drivers/pwm_output.h"
#define QUAD_MOTOR_COUNT 4
@ -105,15 +104,11 @@ typedef struct mixerConfig_s {
PG_DECLARE(mixerConfig_t, mixerConfig);
typedef struct motorConfig_s {
motorDevConfig_t dev;
float digitalIdleOffsetPercent;
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
uint8_t motorPwmProtocol; // Pwm Protocol
uint8_t motorPwmInversion; // Active-High vs Active-Low. Useful for brushed FCs converted for brushless operation
uint8_t useUnsyncedPwm;
float digitalIdleOffsetPercent;
ioTag_t ioTags[MAX_SUPPORTED_MOTORS];
} motorConfig_t;
PG_DECLARE(motorConfig_t, motorConfig);

View File

@ -19,8 +19,7 @@
#include "config/parameter_group.h"
#include "drivers/io_types.h"
#define MAX_SUPPORTED_SERVOS 8
#include "drivers/pwm_output.h"
// These must be consecutive, see 'reversedSources'
enum {
@ -107,11 +106,9 @@ PG_DECLARE_ARRAY(servoParam_t, MAX_SUPPORTED_SERVOS, servoParams);
typedef struct servoConfig_s {
// PWM values, in milliseconds, common range is 1000-2000 (1 to 2ms)
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
uint16_t servoPwmRate; // The update rate of servo outputs (50-498Hz)
servoDevConfig_t dev;
uint16_t servo_lowpass_freq; // lowpass servo filter frequency selection; 1/1000ths of loop freq
uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed
ioTag_t ioTags[MAX_SUPPORTED_SERVOS];
} servoConfig_t;
PG_DECLARE(servoConfig_t, servoConfig);

View File

@ -16,8 +16,3 @@
*/
#pragma once
#include "drivers/io_types.h"
#include "flight/mixer.h"

View File

@ -43,7 +43,7 @@ void targetConfiguration(master_t *config)
config->rxConfig.spektrum_sat_bind_autoreset = 1;
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
config->motorConfig.dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
}
config->profile[0].pidProfile.P8[ROLL] = 90;

View File

@ -85,7 +85,7 @@ void targetConfiguration(master_t *config)
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
config->motorConfig.dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
config->pidConfig.pid_process_denom = 1;
}

View File

@ -62,7 +62,7 @@ void targetConfiguration(master_t *config)
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
if (hardwareMotorType == MOTOR_BRUSHED) {
config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
config->motorConfig.dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
config->pidConfig.pid_process_denom = 1;
}

View File

@ -54,7 +54,7 @@ void targetConfiguration(master_t *config)
config->motorConfig.minthrottle = 1025;
config->motorConfig.maxthrottle = 1980;
config->motorConfig.mincommand = 1000;
config->servoConfig.servoCenterPulse = 1500;
config->servoConfig.dev.servoCenterPulse = 1500;
config->batteryConfig.vbatmaxcellvoltage = 45;
config->batteryConfig.vbatmincellvoltage = 30;

View File

@ -70,7 +70,7 @@ void targetConfiguration(master_t *config)
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->motorConfig.motorPwmRate = 17000;
config->motorConfig.dev.motorPwmRate = 17000;
config->gyroConfig.gyro_sync_denom = 4;
config->pidConfig.pid_process_denom = 1;

View File

@ -43,7 +43,7 @@ void targetConfiguration(master_t *config)
#ifdef BEEBRAIN
// alternative defaults settings for Beebrain target
config->motorConfig.motorPwmRate = 4000;
config->motorConfig.dev.motorPwmRate = 4000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;

View File

@ -27,7 +27,7 @@ extern "C" {
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "io/motors.h"
#include "flight/mixer.h"
//PG_DECLARE(motorConfig_t, motorConfig);
@ -37,7 +37,7 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
.minthrottle = 1150,
.maxthrottle = 1850,
.mincommand = 1000,
.motorPwmRate = 400,
.dev = {.motorPwmRate = 400}
);
}
@ -52,7 +52,7 @@ TEST(ParameterGroupsfTest, Test_pgResetAll)
EXPECT_EQ(1150, motorConfig()->minthrottle);
EXPECT_EQ(1850, motorConfig()->maxthrottle);
EXPECT_EQ(1000, motorConfig()->mincommand);
EXPECT_EQ(400, motorConfig()->motorPwmRate);
EXPECT_EQ(400, motorConfig()->dev.motorPwmRate);
}
TEST(ParameterGroupsfTest, Test_pgFind)
@ -63,16 +63,16 @@ TEST(ParameterGroupsfTest, Test_pgFind)
EXPECT_EQ(1150, motorConfig()->minthrottle);
EXPECT_EQ(1850, motorConfig()->maxthrottle);
EXPECT_EQ(1000, motorConfig()->mincommand);
EXPECT_EQ(400, motorConfig()->motorPwmRate);
EXPECT_EQ(400, motorConfig()->dev.motorPwmRate);
motorConfig_t motorConfig2;
memset(&motorConfig2, 0, sizeof(motorConfig_t));
motorConfigMutable()->motorPwmRate = 500;
motorConfigMutable()->dev.motorPwmRate = 500;
pgStore(pgRegistry, &motorConfig2, sizeof(motorConfig_t), 0);
EXPECT_EQ(1150, motorConfig2.minthrottle);
EXPECT_EQ(1850, motorConfig2.maxthrottle);
EXPECT_EQ(1000, motorConfig2.mincommand);
EXPECT_EQ(500, motorConfig2.motorPwmRate);
EXPECT_EQ(500, motorConfig2.dev.motorPwmRate);
motorConfig_t motorConfig3;
memset(&motorConfig3, 0, sizeof(motorConfig_t));
@ -80,7 +80,7 @@ TEST(ParameterGroupsfTest, Test_pgFind)
EXPECT_EQ(1150, motorConfig3.minthrottle);
EXPECT_EQ(1850, motorConfig3.maxthrottle);
EXPECT_EQ(1000, motorConfig3.mincommand);
EXPECT_EQ(400, motorConfig3.motorPwmRate);
EXPECT_EQ(400, motorConfig3.dev.motorPwmRate);
}
// STUBS

View File

@ -57,6 +57,15 @@ typedef struct
void* test;
} TIM_TypeDef;
typedef struct
{
void* test;
} TIM_OCInitTypeDef;
typedef struct {
void* test;
} DMA_TypeDef;
typedef struct {
void* test;
} DMA_Channel_TypeDef;