Move motorConfig_s, motorDevConfig_s and associated PG handling into pg/motor.[ch]

This commit is contained in:
jflyper 2019-06-29 16:46:14 +09:00
parent f9bd71f9be
commit 0e63596abd
41 changed files with 177 additions and 120 deletions

View File

@ -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"

View File

@ -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"

View File

@ -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"

View File

@ -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"

View File

@ -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;

View File

@ -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)

View File

@ -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 <http://www.gnu.org/licenses/>.
*/
#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

View File

@ -44,6 +44,8 @@
#include "io/serial.h"
#include "pg/motor.h"
typedef enum {
BAUDRATE_NORMAL = 19200,

View File

@ -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;

View File

@ -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"

View File

@ -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"

View File

@ -77,6 +77,7 @@
#include "osd/osd.h"
#include "pg/rx.h"
#include "pg/motor.h"
#include "rx/rx.h"

View File

@ -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

View File

@ -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[];

View File

@ -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"

View File

@ -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"

View File

@ -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"

76
src/main/pg/motor.c Normal file
View File

@ -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 <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#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

46
src/main/pg/motor.h Normal file
View File

@ -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 <http://www.gnu.org/licenses/>.
*/
#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);

View File

@ -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"

View File

@ -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"

View File

@ -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"

View File

@ -37,6 +37,7 @@
#include "flight/pid.h"
#include "pg/rx.h"
#include "pg/motor.h"
#include "rx/rx.h"

View File

@ -36,6 +36,7 @@
#include "flight/pid.h"
#include "pg/rx.h"
#include "pg/motor.h"
#include "rx/rx.h"

View File

@ -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"

View File

@ -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"

View File

@ -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"

View File

@ -38,6 +38,7 @@
#include "io/serial.h"
#include "pg/rx.h"
#include "pg/motor.h"
#include "rx/rx.h"

View File

@ -41,6 +41,7 @@
#include "io/flashfs.h"
#include "io/beeper.h"
#include "pg/motor.h"
#include "pg/rx.h"
#include "rx/rx.h"

View File

@ -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"

View File

@ -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"

View File

@ -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"

View File

@ -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 },

View File

@ -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"

View File

@ -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)

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -50,6 +50,7 @@
#include "io/gps.h"
#include "pg/rx.h"
#include "pg/motor.h"
#include "rx/rx.h"
#include "rx/spektrum.h"

View File

@ -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"

View File

@ -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"