Merge pull request #7700 from mikeller/fix_brushless_detection
Fixed detection of brushless / brushed motors.
This commit is contained in:
commit
722fed4eb7
|
@ -24,33 +24,36 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_BRUSHED_ESC_AUTODETECT
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "pwm_esc_detect.h"
|
||||
#include "timer.h"
|
||||
|
||||
#ifdef USE_BRUSHED_ESC_AUTODETECT
|
||||
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
||||
static uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
||||
|
||||
void detectBrushedESC(void)
|
||||
void detectBrushedESC(ioTag_t motorIoTag)
|
||||
{
|
||||
int i = 0;
|
||||
while (!(TIMER_HARDWARE[i].usageFlags & TIM_USE_MOTOR) && (i < TIMER_CHANNEL_COUNT)) {
|
||||
i++;
|
||||
}
|
||||
IO_t MotorDetectPin = IOGetByTag(TIMER_HARDWARE[i].tag);
|
||||
IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
|
||||
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
|
||||
IO_t motorDetectPin = IOGetByTag(motorIoTag);
|
||||
IOInit(motorDetectPin, OWNER_SYSTEM, 0);
|
||||
IOConfigGPIO(motorDetectPin, IOCFG_IPU);
|
||||
|
||||
delayMicroseconds(10); // allow configuration to settle
|
||||
|
||||
// Check presence of brushed ESC's
|
||||
if (IORead(MotorDetectPin)) {
|
||||
if (IORead(motorDetectPin)) {
|
||||
hardwareMotorType = MOTOR_BRUSHLESS;
|
||||
} else {
|
||||
hardwareMotorType = MOTOR_BRUSHED;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t getDetectedMotorType(void)
|
||||
{
|
||||
return hardwareMotorType;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -20,14 +20,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef USE_BRUSHED_ESC_AUTODETECT
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
typedef enum {
|
||||
MOTOR_UNKNOWN = 0,
|
||||
MOTOR_BRUSHED,
|
||||
MOTOR_BRUSHLESS
|
||||
} HardwareMotorTypes_e;
|
||||
|
||||
extern uint8_t hardwareMotorType;
|
||||
|
||||
void detectBrushedESC(void);
|
||||
#endif
|
||||
void detectBrushedESC(ioTag_t motorIoTag);
|
||||
uint8_t getDetectedMotorType(void);
|
||||
|
|
|
@ -261,7 +261,13 @@ void init(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_BRUSHED_ESC_AUTODETECT
|
||||
detectBrushedESC();
|
||||
// Opportunistically use the first motor pin of the default configuration for detection.
|
||||
// We are doing this as with some boards, timing seems to be important, and the later detection will fail.
|
||||
ioTag_t motorIoTag = timerioTagGetByUsage(TIM_USE_MOTOR, 0);
|
||||
|
||||
if (motorIoTag) {
|
||||
detectBrushedESC(motorIoTag);
|
||||
}
|
||||
#endif
|
||||
|
||||
initEEPROM();
|
||||
|
@ -280,6 +286,15 @@ void init(void)
|
|||
|
||||
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
||||
|
||||
#ifdef USE_BRUSHED_ESC_AUTODETECT
|
||||
// Now detect again with the actually configured pin for motor 1, if it is not the default pin.
|
||||
ioTag_t configuredMotorIoTag = motorConfig()->dev.ioTags[0];
|
||||
|
||||
if (configuredMotorIoTag && configuredMotorIoTag != motorIoTag) {
|
||||
detectBrushedESC(configuredMotorIoTag);
|
||||
}
|
||||
#endif
|
||||
|
||||
//i2cSetOverclock(masterConfig.i2c_overclock);
|
||||
|
||||
debugMode = systemConfig()->debug_mode;
|
||||
|
|
|
@ -86,7 +86,7 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
|
|||
motorConfig->dev.useUnsyncedPwm = true;
|
||||
#else
|
||||
#ifdef USE_BRUSHED_ESC_AUTODETECT
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfig->minthrottle = 1000;
|
||||
motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||
|
|
|
@ -50,7 +50,7 @@ void targetConfiguration(void)
|
|||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
}
|
||||
|
||||
|
|
|
@ -110,7 +110,7 @@ void targetConfiguration(void)
|
|||
parseRcChannels("AETR1234", rxConfigMutable());
|
||||
}
|
||||
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
pidConfigMutable()->pid_process_denom = 1;
|
||||
}
|
||||
|
|
|
@ -57,7 +57,7 @@
|
|||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
pidConfigMutable()->pid_process_denom = 1;
|
||||
}
|
||||
|
|
|
@ -56,7 +56,7 @@
|
|||
// alternative defaults settings for AlienFlight targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
pidConfigMutable()->pid_process_denom = 1;
|
||||
}
|
||||
|
|
|
@ -72,7 +72,7 @@
|
|||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1050; // for 6mm and 7mm brushed
|
||||
}
|
||||
|
|
|
@ -68,7 +68,7 @@
|
|||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1030;
|
||||
pidConfigMutable()->pid_process_denom = 1;
|
||||
|
|
|
@ -54,7 +54,7 @@
|
|||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
if (getDetectedMotorType() == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1049;
|
||||
|
||||
|
|
Loading…
Reference in New Issue