1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 19:40:31 +03:00

Minor update to add motorProtocolFamily_e and move remaining non-motor code out of motor.c

This commit is contained in:
blckmn 2025-01-17 11:49:00 +11:00
parent a9cf384409
commit 93b6bfba48
18 changed files with 117 additions and 55 deletions

View file

@ -108,6 +108,7 @@ COMMON_SRC = \
drivers/motor.c \ drivers/motor.c \
drivers/pinio.c \ drivers/pinio.c \
drivers/pin_pull_up_down.c \ drivers/pin_pull_up_down.c \
drivers/pwm_output.c \
drivers/resource.c \ drivers/resource.c \
drivers/serial.c \ drivers/serial.c \
drivers/serial_impl.c \ drivers/serial_impl.c \

View file

@ -39,7 +39,7 @@
#include "config/feature.h" #include "config/feature.h"
#include "drivers/motor.h" #include "drivers/motor_types.h"
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/dshot_command.h" #include "drivers/dshot_command.h"

View file

@ -138,6 +138,8 @@ void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool pac
void initDshotTelemetry(const timeUs_t looptimeUs); void initDshotTelemetry(const timeUs_t looptimeUs);
void updateDshotTelemetry(void); void updateDshotTelemetry(void);
bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig);
uint16_t getDshotErpm(uint8_t motorIndex); uint16_t getDshotErpm(uint8_t motorIndex);
float getDshotRpm(uint8_t motorIndex); float getDshotRpm(uint8_t motorIndex);
float getDshotRpmAverage(void); float getDshotRpmAverage(void);

View file

@ -132,7 +132,7 @@ void motorRequestTelemetry(unsigned index)
return; return;
} }
if (motorDevice.vTable && motorDevice.vTable->requestTelemetry) { if (motorDevice.vTable->requestTelemetry) {
motorDevice.vTable->requestTelemetry(index); motorDevice.vTable->requestTelemetry(index);
} }
} }
@ -147,24 +147,6 @@ const motorVTable_t *motorGetVTable(void)
return motorDevice.vTable; return motorDevice.vTable;
} }
// This is not motor generic anymore; should be moved to analog pwm module
static void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
{
if (featureIsEnabled(FEATURE_3D)) {
float outputLimitOffset = (flight3DConfig()->limit3d_high - flight3DConfig()->limit3d_low) * (1 - outputLimit) / 2;
*disarm = flight3DConfig()->neutral3d;
*outputLow = flight3DConfig()->limit3d_low + outputLimitOffset;
*outputHigh = flight3DConfig()->limit3d_high - outputLimitOffset;
*deadbandMotor3dHigh = flight3DConfig()->deadband3d_high;
*deadbandMotor3dLow = flight3DConfig()->deadband3d_low;
} else {
*disarm = motorConfig->mincommand;
const float minThrottle = motorConfig->mincommand + motorConfig->motorIdle * 0.1f;
*outputLow = minThrottle;
*outputHigh = motorConfig->maxthrottle - ((motorConfig->maxthrottle - minThrottle) * (1 - outputLimit));
}
}
bool checkMotorProtocolEnabled(const motorDevConfig_t *motorDevConfig, bool *isProtocolDshot) bool checkMotorProtocolEnabled(const motorDevConfig_t *motorDevConfig, bool *isProtocolDshot)
{ {
bool enabled = false; bool enabled = false;
@ -199,6 +181,29 @@ bool checkMotorProtocolEnabled(const motorDevConfig_t *motorDevConfig, bool *isP
return enabled; return enabled;
} }
motorProtocolFamily_e motorGetProtocolFamily(void)
{
switch (motorConfig()->dev.motorProtocol) {
#ifdef USE_PWMOUTPUT
case MOTOR_PROTOCOL_PWM :
case MOTOR_PROTOCOL_ONESHOT125:
case MOTOR_PROTOCOL_ONESHOT42:
case MOTOR_PROTOCOL_MULTISHOT:
case MOTOR_PROTOCOL_BRUSHED:
return MOTOR_PROTOCOL_FAMILY_PWM;
#endif
#ifdef USE_DSHOT
case MOTOR_PROTOCOL_DSHOT150:
case MOTOR_PROTOCOL_DSHOT300:
case MOTOR_PROTOCOL_DSHOT600:
case MOTOR_PROTOCOL_PROSHOT1000:
return MOTOR_PROTOCOL_FAMILY_DSHOT;
#endif
default:
return MOTOR_PROTOCOL_FAMILY_UNKNOWN;
}
}
static void checkMotorProtocol(const motorDevConfig_t *motorDevConfig) static void checkMotorProtocol(const motorDevConfig_t *motorDevConfig)
{ {
motorProtocolEnabled = checkMotorProtocolEnabled(motorDevConfig, &motorProtocolDshot); motorProtocolEnabled = checkMotorProtocolEnabled(motorDevConfig, &motorProtocolDshot);
@ -210,14 +215,21 @@ void motorInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, flo
checkMotorProtocol(&motorConfig->dev); checkMotorProtocol(&motorConfig->dev);
if (isMotorProtocolEnabled()) { if (isMotorProtocolEnabled()) {
if (!isMotorProtocolDshot()) { switch (motorGetProtocolFamily()) {
#ifdef USE_PWM_OUTPUT
case MOTOR_PROTOCOL_FAMILY_PWM:
analogInitEndpoints(motorConfig, outputLimit, outputLow, outputHigh, disarm, deadbandMotor3dHigh, deadbandMotor3dLow); analogInitEndpoints(motorConfig, outputLimit, outputLow, outputHigh, disarm, deadbandMotor3dHigh, deadbandMotor3dLow);
} break;
#ifdef USE_DSHOT
else {
dshotInitEndpoints(motorConfig, outputLimit, outputLow, outputHigh, disarm, deadbandMotor3dHigh, deadbandMotor3dLow);
}
#endif #endif
#ifdef USE_DSHOT
case MOTOR_PROTOCOL_FAMILY_DSHOT:
dshotInitEndpoints(motorConfig, outputLimit, outputLow, outputHigh, disarm, deadbandMotor3dHigh, deadbandMotor3dLow);
break;
#endif
default:
// TODO: perhaps a failure mode here?
break;
}
} }
} }
@ -233,7 +245,7 @@ uint16_t motorConvertToExternal(float motorValue)
void motorPostInit(void) void motorPostInit(void)
{ {
if (motorDevice.vTable && motorDevice.vTable->postInit) { if (motorDevice.vTable->postInit) {
motorDevice.vTable->postInit(); motorDevice.vTable->postInit();
} }
} }
@ -311,7 +323,7 @@ void motorDisable(void)
void motorEnable(void) void motorEnable(void)
{ {
if (motorDevice.initialized && motorDevice.vTable && motorDevice.vTable->enable()) { if (motorDevice.initialized && motorDevice.vTable->enable()) {
motorDevice.enabled = true; motorDevice.enabled = true;
motorDevice.motorEnableTimeMs = millis(); motorDevice.motorEnableTimeMs = millis();
} }
@ -349,20 +361,6 @@ timeMs_t motorGetMotorEnableTimeMs(void)
} }
#endif #endif
//TODO: Remove this function
#ifdef USE_DSHOT_BITBANG
bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig)
{
#if defined(STM32F4) || defined(APM32F4)
return motorDevConfig->useDshotBitbang == DSHOT_BITBANG_ON ||
(motorDevConfig->useDshotBitbang == DSHOT_BITBANG_AUTO && motorDevConfig->useDshotTelemetry && motorDevConfig->motorProtocol != MOTOR_PROTOCOL_PROSHOT1000);
#else
return motorDevConfig->useDshotBitbang == DSHOT_BITBANG_ON ||
(motorDevConfig->useDshotBitbang == DSHOT_BITBANG_AUTO && motorDevConfig->motorProtocol != MOTOR_PROTOCOL_PROSHOT1000);
#endif
}
#endif
/* functions below for empty methods and no active motors */ /* functions below for empty methods and no active motors */
void motorPostInitNull(void) void motorPostInitNull(void)
{ {

View file

@ -46,6 +46,9 @@ void motorDevInit(unsigned motorCount);
unsigned motorDeviceCount(void); unsigned motorDeviceCount(void);
const motorVTable_t *motorGetVTable(void); const motorVTable_t *motorGetVTable(void);
bool checkMotorProtocolEnabled(const motorDevConfig_t *motorConfig, bool *protocolIsDshot); bool checkMotorProtocolEnabled(const motorDevConfig_t *motorConfig, bool *protocolIsDshot);
motorProtocolFamily_e motorGetProtocolFamily(void);
bool isMotorProtocolDshot(void); bool isMotorProtocolDshot(void);
bool isMotorProtocolBidirDshot(void); bool isMotorProtocolBidirDshot(void);
bool isMotorProtocolEnabled(void); bool isMotorProtocolEnabled(void);
@ -58,9 +61,3 @@ bool motorIsMotorEnabled(unsigned index);
bool motorIsMotorIdle(unsigned index); bool motorIsMotorIdle(unsigned index);
timeMs_t motorGetMotorEnableTimeMs(void); timeMs_t motorGetMotorEnableTimeMs(void);
void motorShutdown(void); // Replaces stopPwmAllMotors void motorShutdown(void); // Replaces stopPwmAllMotors
#ifdef USE_DSHOT_BITBANG
struct motorDevConfig_s;
typedef struct motorDevConfig_s motorDevConfig_t;
bool isDshotBitbangActive(const motorDevConfig_t *motorConfig);
#endif

View file

@ -27,6 +27,12 @@
#define MOTOR_OUTPUT_LIMIT_PERCENT_MIN 1 #define MOTOR_OUTPUT_LIMIT_PERCENT_MIN 1
#define MOTOR_OUTPUT_LIMIT_PERCENT_MAX 100 #define MOTOR_OUTPUT_LIMIT_PERCENT_MAX 100
typedef enum {
MOTOR_PROTOCOL_FAMILY_UNKNOWN = 0,
MOTOR_PROTOCOL_FAMILY_PWM,
MOTOR_PROTOCOL_FAMILY_DSHOT,
} motorProtocolFamily_e;
typedef enum { typedef enum {
MOTOR_PROTOCOL_PWM = 0, MOTOR_PROTOCOL_PWM = 0,
MOTOR_PROTOCOL_ONESHOT125, MOTOR_PROTOCOL_ONESHOT125,

View file

@ -0,0 +1,47 @@
/*
* This file is part of Betaflight.
*
* Betaflight is 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.
*
* Betaflight 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#include "pg/motor.h"
#include "fc/rc_controls.h" // for flight3DConfig_t
#include "config/feature.h"
#if defined(USE_PWM_OUTPUT) && defined(USE_MOTOR)
void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
{
if (featureIsEnabled(FEATURE_3D)) {
float outputLimitOffset = (flight3DConfig()->limit3d_high - flight3DConfig()->limit3d_low) * (1 - outputLimit) / 2;
*disarm = flight3DConfig()->neutral3d;
*outputLow = flight3DConfig()->limit3d_low + outputLimitOffset;
*outputHigh = flight3DConfig()->limit3d_high - outputLimitOffset;
*deadbandMotor3dHigh = flight3DConfig()->deadband3d_high;
*deadbandMotor3dLow = flight3DConfig()->deadband3d_low;
} else {
*disarm = motorConfig->mincommand;
const float minThrottle = motorConfig->mincommand + motorConfig->motorIdle * 0.1f;
*outputLow = minThrottle;
*outputHigh = motorConfig->maxthrottle - ((motorConfig->maxthrottle - minThrottle) * (1 - outputLimit));
}
}
#endif

View file

@ -71,3 +71,4 @@ void pwmWriteServo(uint8_t index, float value);
pwmOutputPort_t *pwmGetMotors(void); pwmOutputPort_t *pwmGetMotors(void);
bool pwmIsSynced(void); bool pwmIsSynced(void);
void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow);

View file

@ -188,7 +188,6 @@ MCU_COMMON_SRC = \
STM32/io_stm32.c \ STM32/io_stm32.c \
STM32/light_ws2811strip_stdperiph.c \ STM32/light_ws2811strip_stdperiph.c \
STM32/persistent.c \ STM32/persistent.c \
STM32/pwm_output.c \
STM32/rcc_stm32.c \ STM32/rcc_stm32.c \
STM32/sdio_f4xx.c \ STM32/sdio_f4xx.c \
STM32/serial_uart_stdperiph.c \ STM32/serial_uart_stdperiph.c \

View file

@ -157,7 +157,6 @@ MCU_COMMON_SRC = \
STM32/io_stm32.c \ STM32/io_stm32.c \
STM32/light_ws2811strip_hal.c \ STM32/light_ws2811strip_hal.c \
STM32/persistent.c \ STM32/persistent.c \
STM32/pwm_output.c \
STM32/pwm_output_dshot_hal.c \ STM32/pwm_output_dshot_hal.c \
STM32/rcc_stm32.c \ STM32/rcc_stm32.c \
STM32/sdio_f7xx.c \ STM32/sdio_f7xx.c \

View file

@ -135,7 +135,6 @@ MCU_COMMON_SRC = \
STM32/memprot_hal.c \ STM32/memprot_hal.c \
STM32/memprot_stm32g4xx.c \ STM32/memprot_stm32g4xx.c \
STM32/persistent.c \ STM32/persistent.c \
STM32/pwm_output.c \
STM32/pwm_output_dshot_hal.c \ STM32/pwm_output_dshot_hal.c \
STM32/rcc_stm32.c \ STM32/rcc_stm32.c \
STM32/serial_uart_hal.c \ STM32/serial_uart_hal.c \

View file

@ -163,7 +163,6 @@ MCU_COMMON_SRC = \
STM32/io_stm32.c \ STM32/io_stm32.c \
STM32/light_ws2811strip_hal.c \ STM32/light_ws2811strip_hal.c \
STM32/persistent.c \ STM32/persistent.c \
STM32/pwm_output.c \
STM32/pwm_output_dshot_hal.c \ STM32/pwm_output_dshot_hal.c \
STM32/rcc_stm32.c \ STM32/rcc_stm32.c \
STM32/serial_uart_hal.c \ STM32/serial_uart_hal.c \

View file

@ -284,7 +284,6 @@ MCU_COMMON_SRC = \
STM32/memprot_hal.c \ STM32/memprot_hal.c \
STM32/memprot_stm32h7xx.c \ STM32/memprot_stm32h7xx.c \
STM32/persistent.c \ STM32/persistent.c \
STM32/pwm_output.c \
STM32/pwm_output_dshot_hal.c \ STM32/pwm_output_dshot_hal.c \
STM32/rcc_stm32.c \ STM32/rcc_stm32.c \
STM32/sdio_h7xx.c \ STM32/sdio_h7xx.c \

View file

@ -9,10 +9,10 @@ MCU_COMMON_SRC += \
common/stm32/io_impl.c \ common/stm32/io_impl.c \
common/stm32/serial_uart_hw.c \ common/stm32/serial_uart_hw.c \
common/stm32/dshot_dpwm.c \ common/stm32/dshot_dpwm.c \
STM32/pwm_output_hw.c \
common/stm32/pwm_output_dshot_shared.c \ common/stm32/pwm_output_dshot_shared.c \
common/stm32/dshot_bitbang_shared.c common/stm32/dshot_bitbang_shared.c
SIZE_OPTIMISED_SRC += \ SIZE_OPTIMISED_SRC += \
common/stm32/config_flash.c \ common/stm32/config_flash.c \
common/stm32/bus_spi_pinconfig.c common/stm32/bus_spi_pinconfig.c
@ -21,6 +21,7 @@ SPEED_OPTIMISED_SRC += \
common/stm32/system.c \ common/stm32/system.c \
common/stm32/bus_spi_hw.c \ common/stm32/bus_spi_hw.c \
common/stm32/pwm_output_dshot_shared.c \ common/stm32/pwm_output_dshot_shared.c \
STM32/pwm_output_hw.c \
common/stm32/dshot_bitbang_shared.c \ common/stm32/dshot_bitbang_shared.c \
common/stm32/io_impl.c common/stm32/io_impl.c

View file

@ -32,7 +32,7 @@
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/bus_spi_impl.h" #include "drivers/bus_spi_impl.h"
#include "drivers/dma_reqmap.h" #include "drivers/dma_reqmap.h"
#include "drivers/motor.h" #include "drivers/dshot.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "pg/bus_spi.h" #include "pg/bus_spi.h"

View file

@ -27,6 +27,7 @@
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/motor_types.h" #include "drivers/motor_types.h"
#include "drivers/dshot.h" #include "drivers/dshot.h"
#include "pg/motor.h"
#define USE_DMA_REGISTER_CACHE #define USE_DMA_REGISTER_CACHE

View file

@ -43,3 +43,16 @@ bool bbDshotIsMotorIdle(unsigned motorIndex)
bbMotor_t *const bbmotor = &bbMotors[motorIndex]; bbMotor_t *const bbmotor = &bbMotors[motorIndex];
return bbmotor->protocolControl.value == 0; return bbmotor->protocolControl.value == 0;
} }
#ifdef USE_DSHOT_BITBANG
bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig)
{
#if defined(STM32F4) || defined(APM32F4)
return motorDevConfig->useDshotBitbang == DSHOT_BITBANG_ON ||
(motorDevConfig->useDshotBitbang == DSHOT_BITBANG_AUTO && motorDevConfig->useDshotTelemetry && motorDevConfig->motorProtocol != MOTOR_PROTOCOL_PROSHOT1000);
#else
return motorDevConfig->useDshotBitbang == DSHOT_BITBANG_ON ||
(motorDevConfig->useDshotBitbang == DSHOT_BITBANG_AUTO && motorDevConfig->motorProtocol != MOTOR_PROTOCOL_PROSHOT1000);
#endif
}
#endif