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

Motor code refactor (Phase 1)

This commit is contained in:
jflyper 2019-06-29 03:30:05 +09:00
parent f4bb75180e
commit 542146c702
41 changed files with 1543 additions and 975 deletions

View file

@ -71,7 +71,10 @@ uint8_t cliMode = 0;
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/light_led.h"
#include "drivers/pwm_output.h"
#include "drivers/motor.h"
#include "drivers/dshot.h"
#include "drivers/dshot_dpwm.h"
#include "drivers/dshot_command.h"
#include "drivers/rangefinder/rangefinder_hcsr04.h"
#include "drivers/sdcard.h"
#include "drivers/sensor.h"
@ -1424,9 +1427,11 @@ static void cliSerialPassthrough(char *cmdline)
serialSetCtrlLineStateCb(ports[0].port, cbCtrlLine, (void *)(intptr_t)(port1PinioDtr));
}
// XXX Review ESC pass through under refactored motor handling
#ifdef USE_PWM_OUTPUT
if (escSensorPassthrough) {
pwmDisableMotors();
// pwmDisableMotors();
motorDisable();
delay(5);
unsigned motorsCount = getMotorCount();
for (unsigned i = 0; i < motorsCount; i++) {
@ -3363,7 +3368,7 @@ static void cliRebootEx(rebootTarget_e rebootTarget)
cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter);
waitForSerialPortToFinishTransmitting(cliPort);
stopPwmAllMotors();
motorShutdown();
switch (rebootTarget) {
case REBOOT_TARGET_BOOTLOADER_ROM:
@ -3664,7 +3669,7 @@ static void executeEscInfoCommand(uint8_t escIndex)
startEscDataRead(escInfoBuffer, ESC_INFO_BLHELI32_EXPECTED_FRAME_SIZE);
pwmWriteDshotCommand(escIndex, getMotorCount(), DSHOT_CMD_ESC_INFO, true);
dshotCommandWrite(escIndex, getMotorCount(), DSHOT_CMD_ESC_INFO, true);
delay(10);
@ -3672,6 +3677,9 @@ static void executeEscInfoCommand(uint8_t escIndex)
}
#endif // USE_ESC_SENSOR && USE_ESC_SENSOR_INFO
// XXX Review dshotprog command under refactored motor handling
static void cliDshotProg(char *cmdline)
{
if (isEmpty(cmdline) || motorConfig()->dev.motorPwmProtocol < PWM_TYPE_DSHOT150) {
@ -3699,7 +3707,8 @@ static void cliDshotProg(char *cmdline)
int command = atoi(pch);
if (command >= 0 && command < DSHOT_MIN_THROTTLE) {
if (firstCommand) {
pwmDisableMotors();
// pwmDisableMotors();
motorDisable();
if (command == DSHOT_CMD_ESC_INFO) {
delay(5); // Wait for potential ESC telemetry transmission to finish
@ -3711,7 +3720,7 @@ static void cliDshotProg(char *cmdline)
}
if (command != DSHOT_CMD_ESC_INFO) {
pwmWriteDshotCommand(escIndex, getMotorCount(), command, true);
dshotCommandWrite(escIndex, getMotorCount(), command, true);
} else {
#if defined(USE_ESC_SENSOR) && defined(USE_ESC_SENSOR_INFO)
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
@ -3743,7 +3752,7 @@ static void cliDshotProg(char *cmdline)
pch = strtok_r(NULL, " ", &saveptr);
}
pwmEnableMotors();
motorEnable();
}
#endif // USE_DSHOT
@ -3875,7 +3884,7 @@ static void cliMotor(char *cmdline)
if (motorValue < PWM_RANGE_MIN || motorValue > PWM_RANGE_MAX) {
cliShowArgumentRangeError("VALUE", 1000, 2000);
} else {
uint32_t motorOutputValue = convertExternalToMotor(motorValue);
uint32_t motorOutputValue = motorConvertFromExternal(motorValue);
if (motorIndex != ALL_MOTORS) {
motor_disarmed[motorIndex] = motorOutputValue;
@ -5294,7 +5303,6 @@ static void cliDma(char* cmdline)
}
#endif
static void cliResource(char *cmdline)
{
char *pch = NULL;
@ -5910,7 +5918,7 @@ static void cliMsc(char *cmdline)
cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter);
waitForSerialPortToFinishTransmitting(cliPort);
stopPwmAllMotors();
motorShutdown();
systemResetToMsc(timezoneOffsetMinutes);
} else {