diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 506892c97..ad787be2e 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -45,6 +45,7 @@ #include "config/feature.h" #include "pg/pg.h" #include "pg/pg_ids.h" +#include "pg/motor.h" #include "pg/rx.h" #include "drivers/compass/compass.h" diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 8c785618f..95fe590a7 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -130,6 +130,7 @@ uint8_t cliMode = 0; #include "pg/gyrodev.h" #include "pg/max7456.h" #include "pg/mco.h" +#include "pg/motor.h" #include "pg/pinio.h" #include "pg/pg.h" #include "pg/pg_ids.h" diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index 91d3550ff..3c001dc5c 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -76,6 +76,7 @@ #include "pg/gyrodev.h" #include "pg/max7456.h" #include "pg/mco.h" +#include "pg/motor.h" #include "pg/pg.h" #include "pg/pg_ids.h" #include "pg/pinio.h" diff --git a/src/main/cms/cms_menu_misc.c b/src/main/cms/cms_menu_misc.c index fce15b593..199545a97 100644 --- a/src/main/cms/cms_menu_misc.c +++ b/src/main/cms/cms_menu_misc.c @@ -41,6 +41,7 @@ #include "config/feature.h" #include "pg/pg.h" #include "pg/pg_ids.h" +#include "pg/motor.h" #include "pg/rx.h" #include "fc/config.h" diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 17b18e106..800978280 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -34,6 +34,8 @@ #include "timer.h" #include "drivers/pwm_output.h" +#include "pg/motor.h" + static FAST_RAM_ZERO_INIT pwmWriteFn *pwmWrite; static FAST_RAM_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS]; static FAST_RAM_ZERO_INIT pwmCompleteWriteFn *pwmCompleteWrite = NULL; diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 43ddc19df..6c4a65d89 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -25,9 +25,10 @@ #include "common/time.h" #include "drivers/io_types.h" -#include "drivers/pwm_output_counts.h" #include "drivers/timer.h" +#define BRUSHED_MOTORS_PWM_RATE 16000 +#define BRUSHLESS_MOTORS_PWM_RATE 480 #define ALL_MOTORS 255 #define DSHOT_MAX_COMMAND 47 @@ -220,24 +221,14 @@ typedef struct { IO_t io; } pwmOutputPort_t; -//CAVEAT: This is used in the `motorConfig_t` parameter group, so the parameter group constraints apply -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; - uint8_t useBurstDshot; - uint8_t useDshotTelemetry; - ioTag_t ioTags[MAX_SUPPORTED_MOTORS]; -} motorDevConfig_t; - extern bool useBurstDshot; #ifdef USE_DSHOT_TELEMETRY extern bool useDshotTelemetry; extern uint32_t dshotInvalidPacketCount; #endif -void motorDevInit(const motorDevConfig_t *motorDevConfig, uint16_t idlePulse, uint8_t motorCount); +struct motorDevConfig_s; +void motorDevInit(const struct motorDevConfig_s *motorDevConfig, uint16_t idlePulse, uint8_t motorCount); typedef struct servoDevConfig_s { // PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms) diff --git a/src/main/drivers/pwm_output_counts.h b/src/main/drivers/pwm_output_counts.h deleted file mode 100644 index 0232f2b6c..000000000 --- a/src/main/drivers/pwm_output_counts.h +++ /dev/null @@ -1,34 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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 and Betaflight are distributed in the hope that they - * 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 this software. - * - * If not, see . - */ - -#pragma once - -#include "platform.h" - - -#if defined(USE_QUAD_MIXER_ONLY) -#define MAX_SUPPORTED_MOTORS 4 -#define MAX_SUPPORTED_SERVOS 1 -#else -#ifndef MAX_SUPPORTED_MOTORS -#define MAX_SUPPORTED_MOTORS 8 -#endif -#define MAX_SUPPORTED_SERVOS 8 -#endif diff --git a/src/main/drivers/serial_escserial.c b/src/main/drivers/serial_escserial.c index 99de47b4f..bdd44fcfa 100644 --- a/src/main/drivers/serial_escserial.c +++ b/src/main/drivers/serial_escserial.c @@ -44,6 +44,8 @@ #include "io/serial.h" +#include "pg/motor.h" + typedef enum { BAUDRATE_NORMAL = 19200, diff --git a/src/main/drivers/serial_escserial.h b/src/main/drivers/serial_escserial.h index 1c652aeff..ca1448409 100644 --- a/src/main/drivers/serial_escserial.h +++ b/src/main/drivers/serial_escserial.h @@ -39,7 +39,8 @@ typedef enum { } escProtocol_e; // serialPort API -bool escEnablePassthrough(serialPort_t *escPassthroughPort, const motorDevConfig_t *motorConfig, uint16_t escIndex, uint8_t mode); +struct motorDevConfig_s; +bool escEnablePassthrough(serialPort_t *escPassthroughPort, const struct motorDevConfig_s *motorConfig, uint16_t escIndex, uint8_t mode); typedef struct escSerialConfig_s { ioTag_t ioTag; diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 396480722..a5f46ce18 100644 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -61,6 +61,7 @@ #include "pg/beeper_dev.h" #include "pg/pg.h" #include "pg/pg_ids.h" +#include "pg/motor.h" #include "pg/rx.h" #include "rx/rx.h" diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 74a6fa4a8..ea3d6cb1e 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -138,6 +138,7 @@ #include "pg/bus_quadspi.h" #include "pg/flash.h" #include "pg/mco.h" +#include "pg/motor.h" #include "pg/pinio.h" #include "pg/piniobox.h" #include "pg/pg.h" diff --git a/src/main/fc/tasks.c b/src/main/fc/tasks.c index ce19cf2db..d588e77bc 100644 --- a/src/main/fc/tasks.c +++ b/src/main/fc/tasks.c @@ -77,6 +77,7 @@ #include "osd/osd.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index ff6ad27dd..1d0253c11 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -33,8 +33,8 @@ #include "common/maths.h" #include "config/feature.h" -#include "pg/pg.h" -#include "pg/pg_ids.h" + +#include "pg/motor.h" #include "pg/rx.h" #include "drivers/pwm_output.h" @@ -75,46 +75,6 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, .crashflip_motor_percent = 0, ); -PG_REGISTER_WITH_RESET_FN(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 1); - -void pgResetFn_motorConfig(motorConfig_t *motorConfig) -{ -#ifdef BRUSHED_MOTORS - motorConfig->minthrottle = 1000; - motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED; - motorConfig->dev.useUnsyncedPwm = true; -#else -#ifdef USE_BRUSHED_ESC_AUTODETECT - if (getDetectedMotorType() == MOTOR_BRUSHED) { - motorConfig->minthrottle = 1000; - motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED; - motorConfig->dev.useUnsyncedPwm = true; - } else -#endif - { - motorConfig->minthrottle = 1070; - motorConfig->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE; - motorConfig->dev.motorPwmProtocol = PWM_TYPE_ONESHOT125; - } -#endif - motorConfig->maxthrottle = 2000; - motorConfig->mincommand = 1000; - motorConfig->digitalIdleOffsetValue = 550; -#ifdef USE_DSHOT_DMAR - motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR; -#endif - -#ifdef USE_TIMER - for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) { - motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex); - } -#endif - - motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles -} - PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer, PG_MOTOR_MIXER, 0); #define PWM_RANGE_MID 1500 diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 6b0fdece4..85f50f190 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -24,13 +24,10 @@ #include "common/time.h" #include "pg/pg.h" -#include "drivers/pwm_output_counts.h" #include "drivers/io_types.h" #include "drivers/pwm_output.h" #define QUAD_MOTOR_COUNT 4 -#define BRUSHED_MOTORS_PWM_RATE 16000 -#define BRUSHLESS_MOTORS_PWM_RATE 480 // Digital protocol has fixed values #define DSHOT_3D_FORWARD_MIN_THROTTLE 1048 @@ -91,17 +88,6 @@ typedef struct mixerConfig_s { PG_DECLARE(mixerConfig_t, mixerConfig); -typedef struct motorConfig_s { - motorDevConfig_t dev; - uint16_t digitalIdleOffsetValue; // Idle value for DShot protocol, full motor output = 10000 - 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 - uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry -} motorConfig_t; - -PG_DECLARE(motorConfig_t, motorConfig); - #define CHANNEL_FORWARDING_DISABLED (uint8_t)0xFF extern const mixer_t mixers[]; diff --git a/src/main/flight/rpm_filter.c b/src/main/flight/rpm_filter.c index aa9a962e7..9e7c047ee 100644 --- a/src/main/flight/rpm_filter.c +++ b/src/main/flight/rpm_filter.c @@ -31,12 +31,10 @@ #include "common/filter.h" #include "common/maths.h" -#include "drivers/pwm_output_counts.h" - #include "flight/mixer.h" #include "flight/pid.h" -#include "pg/pg_ids.h" +#include "pg/motor.h" #include "scheduler/scheduler.h" diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index bd48fb901..398bfdc78 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -103,8 +103,7 @@ #include "pg/beeper.h" #include "pg/board.h" #include "pg/gyrodev.h" -#include "pg/pg.h" -#include "pg/pg_ids.h" +#include "pg/motor.h" #include "pg/rx.h" #include "pg/rx_spi.h" #include "pg/usb.h" diff --git a/src/main/osd/osd_elements.c b/src/main/osd/osd_elements.c index 88a0397ca..56d790177 100644 --- a/src/main/osd/osd_elements.c +++ b/src/main/osd/osd_elements.c @@ -93,8 +93,7 @@ #include "osd/osd.h" #include "osd/osd_elements.h" -#include "pg/pg.h" -#include "pg/pg_ids.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/pg/motor.c b/src/main/pg/motor.c new file mode 100644 index 000000000..f3d7ec089 --- /dev/null +++ b/src/main/pg/motor.c @@ -0,0 +1,76 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + + +#include +#include + +#include "platform.h" + +#ifdef USE_MOTOR + +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" + +#include "pg/pg.h" +#include "pg/pg_ids.h" +#include "pg/motor.h" + +PG_REGISTER_WITH_RESET_FN(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 1); + +void pgResetFn_motorConfig(motorConfig_t *motorConfig) +{ +#ifdef BRUSHED_MOTORS + motorConfig->minthrottle = 1000; + motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; + motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED; + motorConfig->dev.useUnsyncedPwm = true; +#else +#ifdef USE_BRUSHED_ESC_AUTODETECT + if (getDetectedMotorType() == MOTOR_BRUSHED) { + motorConfig->minthrottle = 1000; + motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; + motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED; + motorConfig->dev.useUnsyncedPwm = true; + } else +#endif + { + motorConfig->minthrottle = 1070; + motorConfig->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE; + motorConfig->dev.motorPwmProtocol = PWM_TYPE_ONESHOT125; + } +#endif + motorConfig->maxthrottle = 2000; + motorConfig->mincommand = 1000; + motorConfig->digitalIdleOffsetValue = 550; +#ifdef USE_DSHOT_DMAR + motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR; +#endif + +#ifdef USE_TIMER + for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) { + motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex); + } +#endif + + motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles +} + +#endif // USE_MOTOR diff --git a/src/main/pg/motor.h b/src/main/pg/motor.h new file mode 100644 index 000000000..da2eebe6b --- /dev/null +++ b/src/main/pg/motor.h @@ -0,0 +1,46 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#include "pg/pg.h" + +#include "drivers/io.h" + +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; + uint8_t useBurstDshot; + uint8_t useDshotTelemetry; + ioTag_t ioTags[MAX_SUPPORTED_MOTORS]; +} motorDevConfig_t; + +typedef struct motorConfig_s { + motorDevConfig_t dev; + uint16_t digitalIdleOffsetValue; // Idle value for DShot protocol, full motor output = 10000 + 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 + uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry +} motorConfig_t; + +PG_DECLARE(motorConfig_t, motorConfig); diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 8d6226223..ced989e5c 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -31,6 +31,7 @@ #include "config/feature.h" #include "pg/pg.h" #include "pg/pg_ids.h" +#include "pg/motor.h" #include "common/maths.h" #include "common/utils.h" diff --git a/src/main/target/ALIENFLIGHTF1/config.c b/src/main/target/ALIENFLIGHTF1/config.c index ee3d48fbf..676342c3c 100644 --- a/src/main/target/ALIENFLIGHTF1/config.c +++ b/src/main/target/ALIENFLIGHTF1/config.c @@ -31,10 +31,10 @@ #include "fc/config.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c index 74cb262da..f0cec24cc 100644 --- a/src/main/target/ALIENFLIGHTF3/config.c +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -33,12 +33,12 @@ #include "drivers/pwm_esc_detect.h" #include "drivers/sound_beeper.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "pg/beeper_dev.h" #include "pg/gyrodev.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index d970a0daa..dbbd6f44c 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -37,6 +37,7 @@ #include "flight/pid.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/ALIENFLIGHTNGF7/config.c b/src/main/target/ALIENFLIGHTNGF7/config.c index 8c4255dc1..d1ec51473 100644 --- a/src/main/target/ALIENFLIGHTNGF7/config.c +++ b/src/main/target/ALIENFLIGHTNGF7/config.c @@ -36,6 +36,7 @@ #include "flight/pid.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/ALIENWHOOP/config.c b/src/main/target/ALIENWHOOP/config.c index 91374ee26..cf515b30d 100644 --- a/src/main/target/ALIENWHOOP/config.c +++ b/src/main/target/ALIENWHOOP/config.c @@ -57,6 +57,7 @@ #include "io/beeper.h" #include "io/serial.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" #include "sensors/barometer.h" #include "sensors/boardalignment.h" diff --git a/src/main/target/BEEBRAIN_V2F/config.c b/src/main/target/BEEBRAIN_V2F/config.c index 32083efba..fbe888687 100644 --- a/src/main/target/BEEBRAIN_V2F/config.c +++ b/src/main/target/BEEBRAIN_V2F/config.c @@ -39,11 +39,11 @@ #include "fc/rc_modes.h" #include "fc/rc_controls.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "pg/vcd.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/CLRACINGF4/config.c b/src/main/target/CLRACINGF4/config.c index 20e15c99b..73aa9e194 100644 --- a/src/main/target/CLRACINGF4/config.c +++ b/src/main/target/CLRACINGF4/config.c @@ -33,6 +33,7 @@ #include "io/ledstrip.h" #include "fc/config.h" #include "pg/piniobox.h" +#include "pg/motor.h" #include "common/axis.h" #include "sensors/barometer.h" #include "sensors/compass.h" diff --git a/src/main/target/COLIBRI/config.c b/src/main/target/COLIBRI/config.c index 3d0cf1e71..abd7d401d 100644 --- a/src/main/target/COLIBRI/config.c +++ b/src/main/target/COLIBRI/config.c @@ -38,6 +38,7 @@ #include "io/serial.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index 0a3e8677f..a8fb36901 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -41,6 +41,7 @@ #include "io/flashfs.h" #include "io/beeper.h" +#include "pg/motor.h" #include "pg/rx.h" #include "rx/rx.h" diff --git a/src/main/target/FF_PIKOBLX/config.c b/src/main/target/FF_PIKOBLX/config.c index 58c902b2d..9413cd945 100644 --- a/src/main/target/FF_PIKOBLX/config.c +++ b/src/main/target/FF_PIKOBLX/config.c @@ -33,10 +33,10 @@ #include "fc/config.h" #include "fc/controlrate_profile.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/MULTIFLITEPICO/config.c b/src/main/target/MULTIFLITEPICO/config.c index 69fca7ca5..6ee7bbbae 100644 --- a/src/main/target/MULTIFLITEPICO/config.c +++ b/src/main/target/MULTIFLITEPICO/config.c @@ -34,10 +34,10 @@ #include "fc/rc_controls.h" #include "flight/failsafe.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c index 51f2ca569..fcbcf88b8 100644 --- a/src/main/target/NAZE/config.c +++ b/src/main/target/NAZE/config.c @@ -35,7 +35,6 @@ #include "fc/controlrate_profile.h" #include "flight/failsafe.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "pg/rx.h" @@ -48,6 +47,7 @@ #include "pg/beeper_dev.h" #include "pg/flash.h" +#include "pg/motor.h" #include "hardware_revision.h" diff --git a/src/main/target/OMNIBUSF4/config.c b/src/main/target/OMNIBUSF4/config.c index b61858d4e..1931c1180 100644 --- a/src/main/target/OMNIBUSF4/config.c +++ b/src/main/target/OMNIBUSF4/config.c @@ -41,9 +41,10 @@ #include "sensors/barometer.h" #include "sensors/compass.h" #include "sensors/gyro.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "drivers/pwm_output.h" +#include "pg/motor.h" + static targetSerialPortFunction_t targetSerialPortFunction[] = { { SERIAL_PORT_USART1, FUNCTION_RX_SERIAL }, { SERIAL_PORT_USART3, FUNCTION_VTX_SMARTAUDIO }, diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 917d14736..bb724dce2 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -49,6 +49,7 @@ const timerHardware_t timerHardware[1]; // unused #include "scheduler/scheduler.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" diff --git a/src/main/target/SPRACINGF3EVO/config.c b/src/main/target/SPRACINGF3EVO/config.c index ae2fd23b4..618ee4308 100644 --- a/src/main/target/SPRACINGF3EVO/config.c +++ b/src/main/target/SPRACINGF3EVO/config.c @@ -24,10 +24,10 @@ #include "common/axis.h" -#include "flight/mixer.h" #include "flight/pid.h" #include "pg/sdcard.h" +#include "pg/motor.h" #if defined(SPRACINGF3MQ) diff --git a/src/main/target/XILOF4/config.c b/src/main/target/XILOF4/config.c index 9e24134ed..e7e0a558c 100644 --- a/src/main/target/XILOF4/config.c +++ b/src/main/target/XILOF4/config.c @@ -28,6 +28,7 @@ #include "drivers/io.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" #include "io/serial.h" @@ -36,8 +37,8 @@ #include "sensors/battery.h" -#include "flight/mixer.h" #include "flight/pid.h" +#include "flight/mixer.h" #define CURRENT_SCALE 118 diff --git a/src/main/target/common_defaults_post.h b/src/main/target/common_defaults_post.h index 2f2b6950f..c5abfcea4 100644 --- a/src/main/target/common_defaults_post.h +++ b/src/main/target/common_defaults_post.h @@ -598,3 +598,13 @@ #ifndef RTC6705_SPI_INSTANCE #define RTC6705_SPI_INSTANCE NULL #endif + +#if defined(USE_QUAD_MIXER_ONLY) +#define MAX_SUPPORTED_MOTORS 4 +#define MAX_SUPPORTED_SERVOS 1 +#else +#ifndef MAX_SUPPORTED_MOTORS +#define MAX_SUPPORTED_MOTORS 8 +#endif +#define MAX_SUPPORTED_SERVOS 8 +#endif diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index 12f0f301b..b7e48dac2 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -157,6 +157,7 @@ #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot +#define USE_MOTOR #define USE_PWM_OUTPUT #define USE_DMA #define USE_TIMER diff --git a/src/main/telemetry/srxl.c b/src/main/telemetry/srxl.c index eccee71c7..76e977d84 100644 --- a/src/main/telemetry/srxl.c +++ b/src/main/telemetry/srxl.c @@ -50,6 +50,7 @@ #include "io/gps.h" #include "pg/rx.h" +#include "pg/motor.h" #include "rx/rx.h" #include "rx/spektrum.h" diff --git a/src/test/unit/blackbox_unittest.cc b/src/test/unit/blackbox_unittest.cc index 3b978368e..a873ed201 100644 --- a/src/test/unit/blackbox_unittest.cc +++ b/src/test/unit/blackbox_unittest.cc @@ -26,6 +26,7 @@ extern "C" { #include "pg/pg.h" #include "pg/pg_ids.h" #include "pg/rx.h" + #include "pg/motor.h" #include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/gyro_sync.h" diff --git a/src/test/unit/pg_unittest.cc b/src/test/unit/pg_unittest.cc index 415cc5dd6..89d1a6a0d 100644 --- a/src/test/unit/pg_unittest.cc +++ b/src/test/unit/pg_unittest.cc @@ -26,6 +26,7 @@ extern "C" { #include "build/debug.h" #include "pg/pg.h" #include "pg/pg_ids.h" + #include "pg/motor.h" #include "flight/mixer.h"