mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 16:55:29 +03:00
Merge branch 'development' into agh_decl
This commit is contained in:
commit
ec47e3054c
62 changed files with 786 additions and 1195 deletions
|
@ -39,7 +39,6 @@ COMMON_SRC = \
|
|||
drivers/io.c \
|
||||
drivers/io_pca9685.c \
|
||||
drivers/light_led.c \
|
||||
drivers/logging.c \
|
||||
drivers/resource.c \
|
||||
drivers/rx_nrf24l01.c \
|
||||
drivers/rx_spi.c \
|
||||
|
|
|
@ -69,5 +69,6 @@ typedef enum {
|
|||
DEBUG_ACC,
|
||||
DEBUG_GENERIC,
|
||||
DEBUG_ITERM_RELAX,
|
||||
DEBUG_D_BOOST,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -4,9 +4,6 @@
|
|||
#include "drivers/1-wire.h"
|
||||
#include "drivers/1-wire/ds2482.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
|
||||
|
||||
#ifdef USE_1WIRE
|
||||
|
||||
#ifdef USE_1WIRE_DS2482
|
||||
|
@ -17,7 +14,6 @@ static owDev_t ds2482Dev;
|
|||
void owInit(void)
|
||||
{
|
||||
memset(&ds2482Dev, 0, sizeof(ds2482Dev));
|
||||
addBootlogEvent2(BOOT_EVENT_TEMP_SENSOR_DETECTION, BOOT_EVENT_FLAGS_NONE);
|
||||
#ifdef USE_1WIRE_DS2482
|
||||
if (ds2482Detect(&ds2482Dev)) ds2482Detected = true;
|
||||
#endif
|
||||
|
|
|
@ -118,13 +118,13 @@ busDevice_t * busDeviceInit(busType_e bus, devHardwareType_e hw, uint8_t tag, re
|
|||
if (hw == descriptor->devHwType && (bus == descriptor->busType || bus == BUSTYPE_ANY) && (tag == descriptor->tag)) {
|
||||
// We have a candidate - initialize device context memory
|
||||
busDevice_t * dev = descriptor->devicePtr;
|
||||
memset(dev, 0, sizeof(busDevice_t));
|
||||
|
||||
dev->descriptorPtr = descriptor;
|
||||
dev->busType = descriptor->busType;
|
||||
dev->flags = descriptor->flags;
|
||||
|
||||
if (dev) {
|
||||
memset(dev, 0, sizeof(busDevice_t));
|
||||
|
||||
dev->descriptorPtr = descriptor;
|
||||
dev->busType = descriptor->busType;
|
||||
dev->flags = descriptor->flags;
|
||||
|
||||
switch (descriptor->busType) {
|
||||
default:
|
||||
case BUSTYPE_NONE:
|
||||
|
|
|
@ -36,8 +36,6 @@
|
|||
#include "drivers/bus.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
|
||||
|
|
|
@ -1,151 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#ifdef USE_BOOTLOG
|
||||
|
||||
#include "drivers/time.h"
|
||||
|
||||
static bootLogEntry_t events[MAX_BOOTLOG_ENTRIES];
|
||||
static int eventCount;
|
||||
static bool eventOverflow;
|
||||
|
||||
#ifdef BOOTLOG_DESCRIPTIONS
|
||||
static const char * eventDescription[BOOT_EVENT_CODE_COUNT] = {
|
||||
[BOOT_EVENT_CONFIG_LOADED] = "CONFIG_LOADED",
|
||||
[BOOT_EVENT_SYSTEM_INIT_DONE] = "SYSTEM_INIT_DONE",
|
||||
[BOOT_EVENT_PWM_INIT_DONE] = "PWM_INIT_DONE",
|
||||
[BOOT_EVENT_EXTRA_BOOT_DELAY] = "EXTRA_BOOT_DELAY",
|
||||
[BOOT_EVENT_SENSOR_INIT_DONE] = "SENSOR_INIT_DONE",
|
||||
[BOOT_EVENT_GPS_INIT_DONE] = "GPS_INIT_DONE",
|
||||
[BOOT_EVENT_LEDSTRIP_INIT_DONE] = "LEDSTRIP_INIT_DONE",
|
||||
[BOOT_EVENT_TELEMETRY_INIT_DONE] = "TELEMETRY_INIT_DONE",
|
||||
[BOOT_EVENT_SYSTEM_READY] = "SYSTEM_READY",
|
||||
[BOOT_EVENT_GYRO_DETECTION] = "GYRO_DETECTION",
|
||||
[BOOT_EVENT_ACC_DETECTION] = "ACC_DETECTION",
|
||||
[BOOT_EVENT_BARO_DETECTION] = "BARO_DETECTION",
|
||||
[BOOT_EVENT_MAG_DETECTION] = "MAG_DETECTION",
|
||||
[BOOT_EVENT_RANGEFINDER_DETECTION] = "RANGEFINDER_DETECTION",
|
||||
[BOOT_EVENT_MAG_INIT_FAILED] = "MAG_INIT_FAILED",
|
||||
[BOOT_EVENT_HMC5883L_READ_OK_COUNT] = "HMC5883L_READ_OK_COUNT",
|
||||
[BOOT_EVENT_HMC5883L_READ_FAILED] = "HMC5883L_READ_FAILED",
|
||||
[BOOT_EVENT_HMC5883L_SATURATION] = "HMC5883L_SATURATION",
|
||||
[BOOT_EVENT_TIMER_CH_SKIPPED] = "TIMER_CHANNEL_SKIPPED",
|
||||
[BOOT_EVENT_TIMER_CH_MAPPED] = "TIMER_CHANNEL_MAPPED",
|
||||
[BOOT_EVENT_PITOT_DETECTION] = "PITOT_DETECTION",
|
||||
[BOOT_EVENT_TEMP_SENSOR_DETECTION] = "TEMP_SENSOR_DETECTION",
|
||||
[BOOT_EVENT_1WIRE_DETECTION] = "1WIRE_DETECTION",
|
||||
[BOOT_EVENT_HARDWARE_IO_CONFLICT] = "HARDWARE_CONFLICT",
|
||||
[BOOT_EVENT_OPFLOW_DETECTION] = "OPFLOW_DETECTION",
|
||||
};
|
||||
|
||||
const char * getBootlogEventDescription(bootLogEventCode_e eventCode)
|
||||
{
|
||||
if (eventCode < BOOT_EVENT_CODE_COUNT) {
|
||||
return eventDescription[eventCode];
|
||||
}
|
||||
else {
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void initBootlog(void)
|
||||
{
|
||||
memset(events, 0, sizeof(events));
|
||||
eventCount = 0;
|
||||
eventOverflow = false;
|
||||
}
|
||||
|
||||
int getBootlogEventCount(void)
|
||||
{
|
||||
return eventCount;
|
||||
}
|
||||
|
||||
bootLogEntry_t * getBootlogEvent(int index)
|
||||
{
|
||||
if (index <= eventCount) {
|
||||
return &events[index];
|
||||
}
|
||||
else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void addBootlogEntry(bootLogEntry_t * event)
|
||||
{
|
||||
if (eventCount >= MAX_BOOTLOG_ENTRIES) {
|
||||
eventOverflow = true;
|
||||
return;
|
||||
}
|
||||
|
||||
memcpy(&events[eventCount], event, sizeof(bootLogEntry_t));
|
||||
events[eventCount].timestamp = millis();
|
||||
|
||||
eventCount++;
|
||||
}
|
||||
|
||||
void addBootlogEvent2(bootLogEventCode_e eventCode, uint16_t eventFlags)
|
||||
{
|
||||
bootLogEntry_t event;
|
||||
event.eventCode = eventCode;
|
||||
event.eventFlags = eventFlags;
|
||||
addBootlogEntry(&event);
|
||||
}
|
||||
|
||||
void addBootlogEvent4(bootLogEventCode_e eventCode, uint16_t eventFlags, uint32_t param1, uint32_t param2)
|
||||
{
|
||||
bootLogEntry_t event;
|
||||
event.eventCode = eventCode;
|
||||
event.eventFlags = eventFlags | BOOT_EVENT_FLAGS_PARAM32;
|
||||
event.params.u32[0] = param1;
|
||||
event.params.u32[1] = param2;
|
||||
addBootlogEntry(&event);
|
||||
}
|
||||
|
||||
void addBootlogEvent6(bootLogEventCode_e eventCode, uint16_t eventFlags, uint16_t param1, uint16_t param2, uint16_t param3, uint16_t param4)
|
||||
{
|
||||
bootLogEntry_t event;
|
||||
event.eventCode = eventCode;
|
||||
event.eventFlags = eventFlags | BOOT_EVENT_FLAGS_PARAM16;
|
||||
event.params.u16[0] = param1;
|
||||
event.params.u16[1] = param2;
|
||||
event.params.u16[2] = param3;
|
||||
event.params.u16[3] = param4;
|
||||
addBootlogEntry(&event);
|
||||
}
|
||||
#else
|
||||
const char * getBootlogEventDescription(bootLogEventCode_e eventCode) {UNUSED(eventCode);return NULL;}
|
||||
void initBootlog(void) {}
|
||||
int getBootlogEventCount(void) {return 0;}
|
||||
bootLogEntry_t * getBootlogEvent(int index) {UNUSED(index);return NULL;}
|
||||
void addBootlogEvent2(bootLogEventCode_e eventCode, uint16_t eventFlags)
|
||||
{UNUSED(eventCode);UNUSED(eventFlags);}
|
||||
void addBootlogEvent4(bootLogEventCode_e eventCode, uint16_t eventFlags, uint32_t param1, uint32_t param2)
|
||||
{UNUSED(eventCode);UNUSED(eventFlags);UNUSED(param1);UNUSED(param2);}
|
||||
void addBootlogEvent6(bootLogEventCode_e eventCode, uint16_t eventFlags, uint16_t param1, uint16_t param2, uint16_t param3, uint16_t param4)
|
||||
{UNUSED(eventCode);UNUSED(eventFlags);UNUSED(param1);UNUSED(param2);UNUSED(param3);UNUSED(param4);}
|
||||
#endif
|
|
@ -1,38 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "logging_codes.h"
|
||||
|
||||
typedef struct bootLogEntry_s {
|
||||
uint32_t timestamp;
|
||||
uint16_t eventCode;
|
||||
uint16_t eventFlags;
|
||||
union {
|
||||
uint16_t u16[4];
|
||||
uint32_t u32[2];
|
||||
} params;
|
||||
} bootLogEntry_t;
|
||||
|
||||
void initBootlog(void);
|
||||
int getBootlogEventCount(void);
|
||||
bootLogEntry_t * getBootlogEvent(int index);
|
||||
const char * getBootlogEventDescription(bootLogEventCode_e eventCode);
|
||||
void addBootlogEvent2(bootLogEventCode_e eventCode, bootLogFlags_e eventFlags);
|
||||
void addBootlogEvent4(bootLogEventCode_e eventCode, bootLogFlags_e eventFlags, uint32_t param1, uint32_t param2);
|
||||
void addBootlogEvent6(bootLogEventCode_e eventCode, bootLogFlags_e eventFlags, uint16_t param1, uint16_t param2, uint16_t param3, uint16_t param4);
|
|
@ -63,7 +63,8 @@
|
|||
|
||||
// 0x21 // 033 ASCII !
|
||||
|
||||
#define SYM_TRIP_DIST 0x22 // 034 Icon total distance
|
||||
#define SYM_TRIP_DIST 0x22 // 034 Trip distance
|
||||
#define SYM_TOTAL 0x22 // 034 Total
|
||||
|
||||
// 0x23 // 035 ASCII #
|
||||
|
||||
|
|
|
@ -21,228 +21,351 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "common/log.h"
|
||||
#include "common/memory.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/rx_pwm.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
//#include "drivers/rx_pwm.h"
|
||||
|
||||
#include "sensors/rangefinder.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
enum {
|
||||
MAP_TO_NONE,
|
||||
MAP_TO_PPM_INPUT,
|
||||
MAP_TO_PWM_INPUT,
|
||||
MAP_TO_MOTOR_OUTPUT,
|
||||
MAP_TO_SERVO_OUTPUT,
|
||||
};
|
||||
|
||||
static pwmIOConfiguration_t pwmIOConfiguration;
|
||||
typedef struct {
|
||||
int maxTimMotorCount;
|
||||
int maxTimServoCount;
|
||||
const timerHardware_t * timMotors[MAX_PWM_OUTPUT_PORTS];
|
||||
const timerHardware_t * timServos[MAX_PWM_OUTPUT_PORTS];
|
||||
} timMotorServoHardware_t;
|
||||
|
||||
pwmIOConfiguration_t *pwmGetOutputConfiguration(void)
|
||||
static pwmInitError_e pwmInitError = PWM_INIT_ERROR_NONE;
|
||||
|
||||
static const char * pwmInitErrorMsg[] = {
|
||||
/* PWM_INIT_ERROR_NONE */ "No error",
|
||||
/* PWM_INIT_ERROR_TOO_MANY_MOTORS */ "Mixer defines too many motors",
|
||||
/* PWM_INIT_ERROR_TOO_MANY_SERVOS */ "Mixer defines too many servos",
|
||||
/* PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS */ "Not enough motor outputs/timers",
|
||||
/* PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS */ "Not enough servo outputs/timers",
|
||||
/* PWM_INIT_ERROR_TIMER_INIT_FAILED */ "Output timer init failed"
|
||||
};
|
||||
|
||||
static const motorProtocolProperties_t motorProtocolProperties[] = {
|
||||
[PWM_TYPE_STANDARD] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
||||
[PWM_TYPE_ONESHOT125] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
||||
[PWM_TYPE_ONESHOT42] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
||||
[PWM_TYPE_MULTISHOT] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
||||
[PWM_TYPE_BRUSHED] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
||||
[PWM_TYPE_DSHOT150] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
||||
[PWM_TYPE_DSHOT300] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
||||
[PWM_TYPE_DSHOT600] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
||||
[PWM_TYPE_DSHOT1200] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
||||
[PWM_TYPE_SERIALSHOT] = { .usesHwTimer = false, .isDSHOT = false, .isSerialShot = true },
|
||||
};
|
||||
|
||||
pwmInitError_e getPwmInitError(void)
|
||||
{
|
||||
return &pwmIOConfiguration;
|
||||
return pwmInitError;
|
||||
}
|
||||
|
||||
bool CheckGPIOPin(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin)
|
||||
const char * getPwmInitErrorMessage(void)
|
||||
{
|
||||
return IO_GPIOBYTAG(tag) == gpio && IO_PINBYTAG(tag) == pin;
|
||||
return pwmInitErrorMsg[pwmInitError];
|
||||
}
|
||||
|
||||
bool CheckGPIOPinSource(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin)
|
||||
const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto)
|
||||
{
|
||||
return IO_GPIOBYTAG(tag) == gpio && IO_GPIO_PinSource(IOGetByTag(tag)) == pin;
|
||||
return &motorProtocolProperties[proto];
|
||||
}
|
||||
|
||||
pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||
static bool checkPwmTimerConflicts(const timerHardware_t *timHw)
|
||||
{
|
||||
memset(&pwmIOConfiguration, 0, sizeof(pwmIOConfiguration));
|
||||
pwmIOConfiguration.ioConfigurations = memAllocate(sizeof(pwmPortConfiguration_t) * timerHardwareCount, OWNER_PWMIO);
|
||||
serialPortPins_t uartPins;
|
||||
|
||||
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||
int channelIndex = 0;
|
||||
#if defined(USE_UART2)
|
||||
uartGetPortPins(UARTDEV_2, &uartPins);
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART2) && (timHw->tag == uartPins.txPin || timHw->tag == uartPins.rxPin)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
for (int timerIndex = 0; timerIndex < timerHardwareCount; timerIndex++) {
|
||||
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
|
||||
int type = MAP_TO_NONE;
|
||||
|
||||
#if defined(STM32F3) && defined(USE_UART3)
|
||||
// skip UART3 ports (PB10/PB11)
|
||||
if (init->useUART3 && (timerHardwarePtr->tag == IO_TAG(UART3_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART3_RX_PIN))) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#if defined(USE_UART3)
|
||||
uartGetPortPins(UARTDEV_3, &uartPins);
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && (timHw->tag == uartPins.txPin || timHw->tag == uartPins.rxPin)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(UART6_TX_PIN) || defined(UART6_RX_PIN)
|
||||
if (init->useUART6 && (timerHardwarePtr->tag == IO_TAG(UART6_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART6_RX_PIN))) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#if defined(USE_UART4)
|
||||
uartGetPortPins(UARTDEV_4, &uartPins);
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART4) && (timHw->tag == uartPins.txPin || timHw->tag == uartPins.rxPin)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_UART5)
|
||||
uartGetPortPins(UARTDEV_5, &uartPins);
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART5) && (timHw->tag == uartPins.txPin || timHw->tag == uartPins.rxPin)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_UART6)
|
||||
uartGetPortPins(UARTDEV_6, &uartPins);
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART6) && (timHw->tag == uartPins.txPin || timHw->tag == uartPins.rxPin)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_UART7)
|
||||
uartGetPortPins(UARTDEV_7, &uartPins);
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART7) && (timHw->tag == uartPins.txPin || timHw->tag == uartPins.rxPin)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_UART8)
|
||||
uartGetPortPins(UARTDEV_8, &uartPins);
|
||||
if (doesConfigurationUsePort(SERIAL_PORT_USART8) && (timHw->tag == uartPins.txPin || timHw->tag == uartPins.rxPin)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_SOFTSERIAL1)
|
||||
if (init->useSoftSerial) {
|
||||
const timerHardware_t *ss1TimerHardware = timerGetByTag(IO_TAG(SOFTSERIAL_1_RX_PIN), TIM_USE_ANY);
|
||||
if (ss1TimerHardware != NULL && ss1TimerHardware->tim == timerHardwarePtr->tim) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
if (feature(FEATURE_SOFTSERIAL)) {
|
||||
const timerHardware_t *ssrx = timerGetByTag(IO_TAG(SOFTSERIAL_1_RX_PIN), TIM_USE_ANY);
|
||||
const timerHardware_t *sstx = timerGetByTag(IO_TAG(SOFTSERIAL_1_TX_PIN), TIM_USE_ANY);
|
||||
if ((ssrx != NULL && ssrx->tim == timHw->tim) || (sstx != NULL && sstx->tim == timHw->tim)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_SOFTSERIAL2)
|
||||
if (init->useSoftSerial) {
|
||||
const timerHardware_t *ss2TimerHardware = timerGetByTag(IO_TAG(SOFTSERIAL_2_RX_PIN), TIM_USE_ANY);
|
||||
if (ss2TimerHardware != NULL && ss2TimerHardware->tim == timerHardwarePtr->tim) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
if (feature(FEATURE_SOFTSERIAL)) {
|
||||
const timerHardware_t *ssrx = timerGetByTag(IO_TAG(SOFTSERIAL_2_RX_PIN), TIM_USE_ANY);
|
||||
const timerHardware_t *sstx = timerGetByTag(IO_TAG(SOFTSERIAL_2_TX_PIN), TIM_USE_ANY);
|
||||
if ((ssrx != NULL && ssrx->tim == timHw->tim) || (sstx != NULL && sstx->tim == timHw->tim)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_LED_STRIP)
|
||||
// skip LED Strip output
|
||||
if (init->useLEDStrip) {
|
||||
const timerHardware_t * ledTimHw = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
|
||||
if (ledTimHw != NULL && timerHardwarePtr->tim == ledTimHw->tim) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
if (feature(FEATURE_LED_STRIP)) {
|
||||
const timerHardware_t * ledTimHw = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
|
||||
if (ledTimHw != NULL && timHw->tim == ledTimHw->tim) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef VBAT_ADC_PIN
|
||||
if (init->useVbat && timerHardwarePtr->tag == IO_TAG(VBAT_ADC_PIN)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#if defined(USE_ADC)
|
||||
#if defined(ADC_CHANNEL_1_PIN)
|
||||
if (timHw->tag == IO_TAG(ADC_CHANNEL_1_PIN)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
#if defined(ADC_CHANNEL_2_PIN)
|
||||
if (timHw->tag == IO_TAG(ADC_CHANNEL_2_PIN)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
#if defined(ADC_CHANNEL_3_PIN)
|
||||
if (timHw->tag == IO_TAG(ADC_CHANNEL_3_PIN)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
#if defined(ADC_CHANNEL_4_PIN)
|
||||
if (timHw->tag == IO_TAG(ADC_CHANNEL_4_PIN)) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef RSSI_ADC_PIN
|
||||
if (init->useRSSIADC && timerHardwarePtr->tag == IO_TAG(RSSI_ADC_PIN)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CURRENT_METER_ADC_PIN
|
||||
if (init->useCurrentMeterADC && timerHardwarePtr->tag == IO_TAG(CURRENT_METER_ADC_PIN)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_RANGEFINDER_HCSR04
|
||||
if (init->useTriggerRangefinder &&
|
||||
(
|
||||
timerHardwarePtr->tag == init->rangefinderIOConfig.triggerTag ||
|
||||
timerHardwarePtr->tag == init->rangefinderIOConfig.echoTag
|
||||
)) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
// HC-SR04 has a dedicated connection to FC and require two pins
|
||||
if (rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) {
|
||||
const rangefinderHardwarePins_t *rangefinderHardwarePins = rangefinderGetHardwarePins();
|
||||
if (rangefinderHardwarePins && (timHw->tag == rangefinderHardwarePins->triggerTag || timHw->tag == rangefinderHardwarePins->echoTag)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// Handle timer mapping to PWM/PPM inputs
|
||||
if (init->useSerialRx) {
|
||||
type = MAP_TO_NONE;
|
||||
}
|
||||
else if (init->useParallelPWM && (timerHardwarePtr->usageFlags & TIM_USE_PWM)) {
|
||||
type = MAP_TO_PWM_INPUT;
|
||||
}
|
||||
else if (init->usePPM && (timerHardwarePtr->usageFlags & TIM_USE_PPM)) {
|
||||
type = MAP_TO_PPM_INPUT;
|
||||
return false;
|
||||
}
|
||||
|
||||
void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos)
|
||||
{
|
||||
timOutputs->maxTimMotorCount = 0;
|
||||
timOutputs->maxTimServoCount = 0;
|
||||
|
||||
for (int idx = 0; idx < timerHardwareCount; idx++) {
|
||||
const timerHardware_t *timHw = &timerHardware[idx];
|
||||
int type = MAP_TO_NONE;
|
||||
|
||||
// Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC)
|
||||
if (checkPwmTimerConflicts(timHw)) {
|
||||
LOG_W(PWM, "Timer output %d skipped", idx);
|
||||
continue;
|
||||
}
|
||||
|
||||
// Handle outputs - may override the PWM/PPM inputs
|
||||
if (init->flyingPlatformType == PLATFORM_MULTIROTOR || init->flyingPlatformType == PLATFORM_TRICOPTER) {
|
||||
// Determine if timer belongs to motor/servo
|
||||
if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) {
|
||||
// Multicopter
|
||||
if (init->useServoOutputs && (timerHardwarePtr->usageFlags & TIM_USE_MC_SERVO)) {
|
||||
// We enable mapping to servos if mixer is actually using them
|
||||
if (isMixerUsingServos && timHw->usageFlags & TIM_USE_MC_SERVO) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
else if (timerHardwarePtr->usageFlags & TIM_USE_MC_MOTOR) {
|
||||
else if (timHw->usageFlags & TIM_USE_MC_MOTOR) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
} else {
|
||||
// Fixed wing or HELI (one/two motors and a lot of servos
|
||||
if (timerHardwarePtr->usageFlags & TIM_USE_FW_SERVO) {
|
||||
if (timHw->usageFlags & TIM_USE_FW_SERVO) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
else if (timerHardwarePtr->usageFlags & TIM_USE_FW_MOTOR) {
|
||||
else if (timHw->usageFlags & TIM_USE_FW_MOTOR) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
}
|
||||
|
||||
// If timer not mapped - skip
|
||||
if (type == MAP_TO_NONE)
|
||||
continue;
|
||||
|
||||
if (type == MAP_TO_PPM_INPUT) {
|
||||
#if defined(USE_RX_PPM)
|
||||
ppmInConfig(timerHardwarePtr);
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_PPM;
|
||||
pwmIOConfiguration.ppmInputCount++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 0);
|
||||
#endif
|
||||
} else if (type == MAP_TO_PWM_INPUT) {
|
||||
#if defined(USE_RX_PWM)
|
||||
pwmInConfig(timerHardwarePtr, channelIndex);
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_PWM;
|
||||
pwmIOConfiguration.pwmInputCount++;
|
||||
channelIndex++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 1);
|
||||
#endif
|
||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||
/* Check if we already configured maximum supported number of motors and skip the rest */
|
||||
if (pwmIOConfiguration.motorCount >= MAX_MOTORS) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 2);
|
||||
continue;
|
||||
}
|
||||
|
||||
if (pwmMotorConfig(timerHardwarePtr, pwmIOConfiguration.motorCount, motorConfig()->motorPwmRate, init->enablePWMOutput)) {
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_MOTOR;
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].index = pwmIOConfiguration.motorCount;
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].timerHardware = timerHardwarePtr;
|
||||
|
||||
pwmIOConfiguration.motorCount++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 2);
|
||||
}
|
||||
else {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 2);
|
||||
continue;
|
||||
}
|
||||
} else if (type == MAP_TO_SERVO_OUTPUT) {
|
||||
if (pwmIOConfiguration.servoCount >= MAX_SERVOS) {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
|
||||
if (pwmServoConfig(timerHardwarePtr, pwmIOConfiguration.servoCount, init->servoPwmRate, init->servoCenterPulse, init->enablePWMOutput)) {
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_SERVO;
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].index = pwmIOConfiguration.servoCount;
|
||||
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].timerHardware = timerHardwarePtr;
|
||||
|
||||
pwmIOConfiguration.servoCount++;
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_MAPPED, BOOT_EVENT_FLAGS_NONE, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
}
|
||||
else {
|
||||
addBootlogEvent6(BOOT_EVENT_TIMER_CH_SKIPPED, BOOT_EVENT_FLAGS_WARNING, timerIndex, pwmIOConfiguration.motorCount, pwmIOConfiguration.servoCount, 3);
|
||||
continue;
|
||||
}
|
||||
} else {
|
||||
continue;
|
||||
switch(type) {
|
||||
case MAP_TO_MOTOR_OUTPUT:
|
||||
timOutputs->timMotors[timOutputs->maxTimMotorCount++] = timHw;
|
||||
break;
|
||||
case MAP_TO_SERVO_OUTPUT:
|
||||
timOutputs->timServos[timOutputs->maxTimServoCount++] = timHw;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
pwmIOConfiguration.ioCount++;
|
||||
static bool motorsUseHardwareTimers(void)
|
||||
{
|
||||
return getMotorProtocolProperties(motorConfig()->motorPwmProtocol)->usesHwTimer;
|
||||
}
|
||||
|
||||
static bool servosUseHardwareTimers(void)
|
||||
{
|
||||
return !feature(FEATURE_PWM_SERVO_DRIVER);
|
||||
}
|
||||
|
||||
static void pwmInitMotors(timMotorServoHardware_t * timOutputs)
|
||||
{
|
||||
const int motorCount = getMotorCount();
|
||||
|
||||
// Check if too many motors
|
||||
if (motorCount > MAX_MOTORS) {
|
||||
pwmInitError = PWM_INIT_ERROR_TOO_MANY_MOTORS;
|
||||
LOG_E(PWM, "Too many motors. Mixer requested %d, max %d", motorCount, MAX_MOTORS);
|
||||
return;
|
||||
}
|
||||
|
||||
return &pwmIOConfiguration;
|
||||
// Do the pre-configuration. For motors w/o hardware timers this should be sufficient
|
||||
pwmMotorPreconfigure();
|
||||
|
||||
// Now if we need to configure individual motor outputs - do that
|
||||
if (!motorsUseHardwareTimers()) {
|
||||
LOG_I(PWM, "Skipped timer init for motors");
|
||||
return;
|
||||
}
|
||||
|
||||
// If mixer requests more motors than we have timer outputs - throw an error
|
||||
if (motorCount > timOutputs->maxTimMotorCount) {
|
||||
pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS;
|
||||
LOG_E(PWM, "Not enough motor outputs. Mixer requested %d, outputs %d", motorCount, timOutputs->maxTimMotorCount);
|
||||
return;
|
||||
}
|
||||
|
||||
// Finally initialize individual motor outputs
|
||||
for (int idx = 0; idx < motorCount; idx++) {
|
||||
const timerHardware_t *timHw = timOutputs->timMotors[idx];
|
||||
if (!pwmMotorConfig(timHw, idx, feature(FEATURE_PWM_OUTPUT_ENABLE))) {
|
||||
pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED;
|
||||
LOG_E(PWM, "Timer allocation failed for motor %d", idx);
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void pwmInitServos(timMotorServoHardware_t * timOutputs)
|
||||
{
|
||||
const int servoCount = getServoCount();
|
||||
|
||||
if (!isMixerUsingServos()) {
|
||||
LOG_I(PWM, "Mixer does not use servos");
|
||||
return;
|
||||
}
|
||||
|
||||
// Check if too many servos
|
||||
if (servoCount > MAX_SERVOS) {
|
||||
pwmInitError = PWM_INIT_ERROR_TOO_MANY_SERVOS;
|
||||
LOG_E(PWM, "Too many servos. Mixer requested %d, max %d", servoCount, MAX_SERVOS);
|
||||
return;
|
||||
}
|
||||
|
||||
// Do the pre-configuration. This should configure non-timer PWM drivers
|
||||
pwmServoPreconfigure();
|
||||
|
||||
// Check if we need to init timer output for servos
|
||||
if (!servosUseHardwareTimers()) {
|
||||
// External PWM servo driver
|
||||
LOG_I(PWM, "Skipped timer init for servos - using external servo driver");
|
||||
return;
|
||||
}
|
||||
|
||||
// If mixer requests more servos than we have timer outputs - throw an error
|
||||
if (servoCount > timOutputs->maxTimServoCount) {
|
||||
pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS;
|
||||
LOG_E(PWM, "Too many servos. Mixer requested %d, timer outputs %d", servoCount, timOutputs->maxTimServoCount);
|
||||
return;
|
||||
}
|
||||
|
||||
// Configure individual servo outputs
|
||||
for (int idx = 0; idx < servoCount; idx++) {
|
||||
const timerHardware_t *timHw = timOutputs->timServos[idx];
|
||||
|
||||
if (!pwmServoConfig(timHw, idx, servoConfig()->servoPwmRate, servoConfig()->servoCenterPulse, feature(FEATURE_PWM_OUTPUT_ENABLE))) {
|
||||
pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED;
|
||||
LOG_E(PWM, "Timer allocation failed for servo %d", idx);
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
bool pwmMotorAndServoInit(void)
|
||||
{
|
||||
timMotorServoHardware_t timOutputs;
|
||||
|
||||
// Build temporary timer mappings for motor and servo
|
||||
pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos());
|
||||
|
||||
// At this point we have built tables of timers suitable for motor and servo mappings
|
||||
// Now we can actually initialize them according to motor/servo count from mixer
|
||||
pwmInitMotors(&timOutputs);
|
||||
pwmInitServos(&timOutputs);
|
||||
|
||||
return (pwmInitError == PWM_INIT_ERROR_NONE);
|
||||
}
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
|
||||
#include "drivers/io_types.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#if defined(TARGET_MOTOR_COUNT)
|
||||
#define MAX_PWM_MOTORS TARGET_MOTOR_COUNT
|
||||
|
@ -39,87 +40,40 @@
|
|||
|
||||
#define MAX_INPUTS 8
|
||||
|
||||
typedef enum {
|
||||
PWM_TYPE_STANDARD = 0,
|
||||
PWM_TYPE_ONESHOT125,
|
||||
PWM_TYPE_ONESHOT42,
|
||||
PWM_TYPE_MULTISHOT,
|
||||
PWM_TYPE_BRUSHED,
|
||||
PWM_TYPE_DSHOT150,
|
||||
PWM_TYPE_DSHOT300,
|
||||
PWM_TYPE_DSHOT600,
|
||||
PWM_TYPE_DSHOT1200,
|
||||
PWM_TYPE_SERIALSHOT,
|
||||
} motorPwmProtocolTypes_e;
|
||||
|
||||
typedef enum {
|
||||
PWM_INIT_ERROR_NONE = 0,
|
||||
PWM_INIT_ERROR_TOO_MANY_MOTORS,
|
||||
PWM_INIT_ERROR_TOO_MANY_SERVOS,
|
||||
PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS,
|
||||
PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS,
|
||||
PWM_INIT_ERROR_TIMER_INIT_FAILED,
|
||||
} pwmInitError_e;
|
||||
|
||||
typedef struct rangefinderIOConfig_s {
|
||||
ioTag_t triggerTag;
|
||||
ioTag_t echoTag;
|
||||
} rangefinderIOConfig_t;
|
||||
|
||||
typedef struct drv_pwm_config_s {
|
||||
int flyingPlatformType;
|
||||
typedef struct {
|
||||
bool usesHwTimer;
|
||||
bool isDSHOT;
|
||||
bool isSerialShot;
|
||||
} motorProtocolProperties_t;
|
||||
|
||||
bool enablePWMOutput;
|
||||
bool useParallelPWM;
|
||||
bool usePPM;
|
||||
bool useSerialRx;
|
||||
bool useRSSIADC;
|
||||
bool useCurrentMeterADC;
|
||||
bool useUART2;
|
||||
bool useUART3;
|
||||
bool useUART6;
|
||||
bool useVbat;
|
||||
bool useSoftSerial;
|
||||
bool useLEDStrip;
|
||||
#ifdef USE_RANGEFINDER
|
||||
bool useTriggerRangefinder;
|
||||
#endif
|
||||
bool useServoOutputs;
|
||||
uint16_t servoPwmRate;
|
||||
uint16_t servoCenterPulse;
|
||||
rangefinderIOConfig_t rangefinderIOConfig;
|
||||
} drv_pwm_config_t;
|
||||
|
||||
typedef enum {
|
||||
PWM_PF_NONE = 0,
|
||||
PWM_PF_MOTOR = (1 << 0),
|
||||
PWM_PF_SERVO = (1 << 1),
|
||||
PWM_PF_PPM = (1 << 5),
|
||||
PWM_PF_PWM = (1 << 6)
|
||||
} pwmPortFlags_e;
|
||||
|
||||
struct timerHardware_s;
|
||||
typedef struct pwmPortConfiguration_s {
|
||||
uint8_t index;
|
||||
pwmPortFlags_e flags;
|
||||
const struct timerHardware_s *timerHardware;
|
||||
} pwmPortConfiguration_t;
|
||||
|
||||
typedef struct pwmIOConfiguration_s {
|
||||
uint8_t servoCount;
|
||||
uint8_t motorCount;
|
||||
uint8_t ioCount;
|
||||
uint8_t pwmInputCount;
|
||||
uint8_t ppmInputCount;
|
||||
pwmPortConfiguration_t * ioConfigurations;
|
||||
} pwmIOConfiguration_t;
|
||||
|
||||
// This indexes into the read-only hardware definition structure, timerHardware_t
|
||||
enum {
|
||||
PWM1 = 0,
|
||||
PWM2,
|
||||
PWM3,
|
||||
PWM4,
|
||||
PWM5,
|
||||
PWM6,
|
||||
PWM7,
|
||||
PWM8,
|
||||
PWM9,
|
||||
PWM10,
|
||||
PWM11,
|
||||
PWM12,
|
||||
PWM13,
|
||||
PWM14,
|
||||
PWM15,
|
||||
PWM16,
|
||||
PWM17,
|
||||
PWM18,
|
||||
PWM19,
|
||||
PWM20
|
||||
};
|
||||
|
||||
extern const uint16_t multiPPM[];
|
||||
extern const uint16_t multiPWM[];
|
||||
extern const uint16_t airPPM[];
|
||||
extern const uint16_t airPWM[];
|
||||
|
||||
pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init);
|
||||
pwmIOConfiguration_t *pwmGetOutputConfiguration(void);
|
||||
bool pwmMotorAndServoInit(void);
|
||||
const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto);
|
||||
pwmInitError_e getPwmInitError(void);
|
||||
const char * getPwmInitErrorMessage(void);
|
||||
|
|
|
@ -83,12 +83,12 @@ typedef struct {
|
|||
|
||||
static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS];
|
||||
|
||||
static pwmOutputMotor_t motors[MAX_PWM_MOTORS];
|
||||
static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
|
||||
|
||||
static pwmOutputMotor_t motors[MAX_PWM_MOTORS];
|
||||
static motorPwmProtocolTypes_e initMotorProtocol;
|
||||
static pwmWriteFuncPtr motorWritePtr = NULL; // Function to write value to motors
|
||||
|
||||
static pwmOutputPort_t * servos[MAX_PWM_SERVOS];
|
||||
static pwmWriteFuncPtr servoWritePtr = NULL; // Function to write value to motors
|
||||
|
||||
#if defined(USE_DSHOT) || defined(USE_SERIALSHOT)
|
||||
static timeUs_t digitalMotorUpdateIntervalUs = 0;
|
||||
|
@ -164,6 +164,12 @@ static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t
|
|||
return p;
|
||||
}
|
||||
|
||||
static void pwmWriteNull(uint8_t index, uint16_t value)
|
||||
{
|
||||
(void)index;
|
||||
(void)value;
|
||||
}
|
||||
|
||||
static void pwmWriteStandard(uint8_t index, uint16_t value)
|
||||
{
|
||||
if (motors[index].pwmPort) {
|
||||
|
@ -237,19 +243,15 @@ uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType)
|
|||
}
|
||||
}
|
||||
|
||||
static pwmOutputPort_t * motorConfigDshot(const timerHardware_t * timerHardware, motorPwmProtocolTypes_e proto, uint16_t motorPwmRateHz, bool enableOutput)
|
||||
static pwmOutputPort_t * motorConfigDshot(const timerHardware_t * timerHardware, uint32_t dshotHz, bool enableOutput)
|
||||
{
|
||||
// Try allocating new port
|
||||
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, getDshotHz(proto), DSHOT_MOTOR_BITLENGTH, 0, enableOutput);
|
||||
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, dshotHz, DSHOT_MOTOR_BITLENGTH, 0, enableOutput);
|
||||
|
||||
if (!port) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// Keep track of motor update interval
|
||||
const timeUs_t motorIntervalUs = 1000000 / motorPwmRateHz;
|
||||
digitalMotorUpdateIntervalUs = MAX(digitalMotorUpdateIntervalUs, motorIntervalUs);
|
||||
|
||||
// Configure timer DMA
|
||||
if (timerPWMConfigChannelDMA(port->tch, port->dmaBuffer, sizeof(port->dmaBuffer[0]), DSHOT_DMA_BUFFER_SIZE)) {
|
||||
// Only mark as DSHOT channel if DMA was set successfully
|
||||
|
@ -288,19 +290,13 @@ static uint16_t prepareDshotPacket(const uint16_t value, bool requestTelemetry)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERIALSHOT
|
||||
static void motorConfigSerialShot(uint16_t motorPwmRateHz)
|
||||
{
|
||||
// Keep track of motor update interval
|
||||
const timeUs_t motorIntervalUs = 1000000 / motorPwmRateHz;
|
||||
digitalMotorUpdateIntervalUs = MAX(digitalMotorUpdateIntervalUs, motorIntervalUs);
|
||||
|
||||
// Kick off SerialShot driver initalization
|
||||
serialshotInitialize();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_DSHOT) || defined(USE_SERIALSHOT)
|
||||
static void motorConfigDigitalUpdateInterval(uint16_t motorPwmRateHz)
|
||||
{
|
||||
digitalMotorUpdateIntervalUs = 1000000 / motorPwmRateHz;
|
||||
digitalMotorLastUpdateUs = 0;
|
||||
}
|
||||
|
||||
static void pwmWriteDigital(uint8_t index, uint16_t value)
|
||||
{
|
||||
// Just keep track of motor value, actual update happens in pwmCompleteMotorUpdate()
|
||||
|
@ -312,15 +308,12 @@ bool FAST_CODE NOINLINE isMotorProtocolDshot(void)
|
|||
{
|
||||
// We look at cached `initMotorProtocol` to make sure we are consistent with the initialized config
|
||||
// motorConfig()->motorPwmProtocol may change at run time which will cause uninitialized structures to be used
|
||||
return (initMotorProtocol == PWM_TYPE_DSHOT150) ||
|
||||
(initMotorProtocol == PWM_TYPE_DSHOT300) ||
|
||||
(initMotorProtocol == PWM_TYPE_DSHOT600) ||
|
||||
(initMotorProtocol == PWM_TYPE_DSHOT1200);
|
||||
return getMotorProtocolProperties(initMotorProtocol)->isDSHOT;
|
||||
}
|
||||
|
||||
bool FAST_CODE NOINLINE isMotorProtocolSerialShot(void)
|
||||
{
|
||||
return (initMotorProtocol == PWM_TYPE_SERIALSHOT);
|
||||
return getMotorProtocolProperties(initMotorProtocol)->isSerialShot;
|
||||
}
|
||||
|
||||
bool FAST_CODE NOINLINE isMotorProtocolDigital(void)
|
||||
|
@ -377,7 +370,7 @@ void pwmCompleteMotorUpdate(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRateHz, bool enableOutput)
|
||||
void pwmMotorPreconfigure(void)
|
||||
{
|
||||
// Keep track of initial motor protocol
|
||||
initMotorProtocol = motorConfig()->motorPwmProtocol;
|
||||
|
@ -386,25 +379,58 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, ui
|
|||
initMotorProtocol = PWM_TYPE_BRUSHED; // Override proto
|
||||
#endif
|
||||
|
||||
// Protocol-specific configuration
|
||||
switch (initMotorProtocol) {
|
||||
default:
|
||||
motorWritePtr = pwmWriteNull;
|
||||
break;
|
||||
|
||||
case PWM_TYPE_STANDARD:
|
||||
case PWM_TYPE_BRUSHED:
|
||||
case PWM_TYPE_ONESHOT125:
|
||||
case PWM_TYPE_ONESHOT42:
|
||||
case PWM_TYPE_MULTISHOT:
|
||||
motorWritePtr = pwmWriteStandard;
|
||||
break;
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
case PWM_TYPE_DSHOT1200:
|
||||
case PWM_TYPE_DSHOT600:
|
||||
case PWM_TYPE_DSHOT300:
|
||||
case PWM_TYPE_DSHOT150:
|
||||
motorConfigDigitalUpdateInterval(motorConfig()->motorPwmRate);
|
||||
motorWritePtr = pwmWriteDigital;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERIALSHOT
|
||||
case PWM_TYPE_SERIALSHOT:
|
||||
// Kick off SerialShot driver initalization
|
||||
serialshotInitialize();
|
||||
motorConfigDigitalUpdateInterval(motorConfig()->motorPwmRate);
|
||||
motorWritePtr = pwmWriteDigital;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bool enableOutput)
|
||||
{
|
||||
switch (initMotorProtocol) {
|
||||
case PWM_TYPE_BRUSHED:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 0.0f, 0.0f, motorPwmRateHz, enableOutput);
|
||||
motorWritePtr = pwmWriteStandard;
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 0.0f, 0.0f, motorConfig()->motorPwmRate, enableOutput);
|
||||
break;
|
||||
|
||||
case PWM_TYPE_ONESHOT125:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorPwmRateHz, enableOutput);
|
||||
motorWritePtr = pwmWriteStandard;
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorConfig()->motorPwmRate, enableOutput);
|
||||
break;
|
||||
|
||||
case PWM_TYPE_ONESHOT42:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 42e-6f, 42e-6f, motorPwmRateHz, enableOutput);
|
||||
motorWritePtr = pwmWriteStandard;
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 42e-6f, 42e-6f, motorConfig()->motorPwmRate, enableOutput);
|
||||
break;
|
||||
|
||||
case PWM_TYPE_MULTISHOT:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorPwmRateHz, enableOutput);
|
||||
motorWritePtr = pwmWriteStandard;
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorConfig()->motorPwmRate, enableOutput);
|
||||
break;
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
|
@ -412,35 +438,62 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, ui
|
|||
case PWM_TYPE_DSHOT600:
|
||||
case PWM_TYPE_DSHOT300:
|
||||
case PWM_TYPE_DSHOT150:
|
||||
motors[motorIndex].pwmPort = motorConfigDshot(timerHardware, initMotorProtocol, motorPwmRateHz, enableOutput);
|
||||
motorWritePtr = pwmWriteDigital;
|
||||
motors[motorIndex].pwmPort = motorConfigDshot(timerHardware, getDshotHz(initMotorProtocol), enableOutput);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERIALSHOT
|
||||
case PWM_TYPE_SERIALSHOT:
|
||||
// This is hacky. Our motor output flow is: init() -> pwmInit() -> pwmMotorConfig()
|
||||
// This is decoupled from mixer, so if the board doesn't define any PWM motor output the pwmMotorConfig() won't get called
|
||||
// We rely on the fact that all FCs define hardware PWM motor outputs. To make this bullet-proof we need to change the
|
||||
// init sequence to originate from the mixer and allocate timers only if necessary
|
||||
motorConfigSerialShot(motorPwmRateHz);
|
||||
// Make sure pwmMotorConfig fails and doesn't mark timer as occupied by a motor
|
||||
motors[motorIndex].pwmPort = NULL;
|
||||
// Serialshot uses the same throttle interpretation as DSHOT, so we use the same write function here
|
||||
motorWritePtr = pwmWriteDigital;
|
||||
case PWM_TYPE_STANDARD:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, motorConfig()->motorPwmRate, enableOutput);
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
case PWM_TYPE_STANDARD:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, motorPwmRateHz, enableOutput);
|
||||
motorWritePtr = pwmWriteStandard;
|
||||
motors[motorIndex].pwmPort = NULL;
|
||||
break;
|
||||
}
|
||||
|
||||
return (motors[motorIndex].pwmPort != NULL);
|
||||
}
|
||||
|
||||
// Helper function for ESC passthrough
|
||||
ioTag_t pwmGetMotorPinTag(int motorIndex)
|
||||
{
|
||||
if (motors[motorIndex].pwmPort) {
|
||||
return motors[motorIndex].pwmPort->tch->timHw->tag;
|
||||
}
|
||||
else {
|
||||
return IOTAG_NONE;
|
||||
}
|
||||
}
|
||||
|
||||
static void pwmServoWriteStandard(uint8_t index, uint16_t value)
|
||||
{
|
||||
if (servos[index]) {
|
||||
*servos[index]->ccr = value;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
static void pwmServoWriteExternalDriver(uint8_t index, uint16_t value)
|
||||
{
|
||||
// If PCA9685 is not detected, we do not want to write servo output anywhere
|
||||
if (STATE(PWM_DRIVER_AVAILABLE)) {
|
||||
pwmDriverSetPulse(index, value);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void pwmServoPreconfigure(void)
|
||||
{
|
||||
servoWritePtr = pwmServoWriteStandard;
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
// If PCA9685 is enabled - switch the servo write function to external
|
||||
if (feature(FEATURE_PWM_SERVO_DRIVER)) {
|
||||
servoWritePtr = pwmServoWriteExternalDriver;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
bool pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput)
|
||||
{
|
||||
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, PWM_TIMER_HZ, PWM_TIMER_HZ / servoPwmRate, servoCenterPulse, enableOutput);
|
||||
|
@ -455,23 +508,9 @@ bool pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui
|
|||
|
||||
void pwmWriteServo(uint8_t index, uint16_t value)
|
||||
{
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
|
||||
/*
|
||||
* If PCA9685 is enabled and but not detected, we do not want to write servo
|
||||
* output anywhere
|
||||
*/
|
||||
if (feature(FEATURE_PWM_SERVO_DRIVER) && STATE(PWM_DRIVER_AVAILABLE)) {
|
||||
pwmDriverSetPulse(index, value);
|
||||
} else if (!feature(FEATURE_PWM_SERVO_DRIVER) && servos[index] && index < MAX_SERVOS) {
|
||||
*servos[index]->ccr = value;
|
||||
if (servoWritePtr && index < MAX_SERVOS) {
|
||||
servoWritePtr(index, value);
|
||||
}
|
||||
|
||||
#else
|
||||
if (servos[index] && index < MAX_SERVOS) {
|
||||
*servos[index]->ccr = value;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef BEEPER_PWM
|
||||
|
|
|
@ -20,18 +20,7 @@
|
|||
#include "drivers/io_types.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
typedef enum {
|
||||
PWM_TYPE_STANDARD = 0,
|
||||
PWM_TYPE_ONESHOT125,
|
||||
PWM_TYPE_ONESHOT42,
|
||||
PWM_TYPE_MULTISHOT,
|
||||
PWM_TYPE_BRUSHED,
|
||||
PWM_TYPE_DSHOT150,
|
||||
PWM_TYPE_DSHOT300,
|
||||
PWM_TYPE_DSHOT600,
|
||||
PWM_TYPE_DSHOT1200,
|
||||
PWM_TYPE_SERIALSHOT,
|
||||
} motorPwmProtocolTypes_e;
|
||||
ioTag_t pwmGetMotorPinTag(int motorIndex);
|
||||
|
||||
void pwmWriteMotor(uint8_t index, uint16_t value);
|
||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
|
||||
|
@ -43,7 +32,11 @@ void pwmWriteServo(uint8_t index, uint16_t value);
|
|||
void pwmDisableMotors(void);
|
||||
void pwmEnableMotors(void);
|
||||
struct timerHardware_s;
|
||||
bool pwmMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, bool enableOutput);
|
||||
|
||||
void pwmMotorPreconfigure(void);
|
||||
bool pwmMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, bool enableOutput);
|
||||
|
||||
void pwmServoPreconfigure(void);
|
||||
bool pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput);
|
||||
void pwmWriteBeeper(bool onoffBeep);
|
||||
void beeperPwmInit(ioTag_t tag, uint16_t frequency);
|
|
@ -32,8 +32,6 @@
|
|||
#include "drivers/nvic.h"
|
||||
#include "drivers/rcc.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#include "drivers/rangefinder/rangefinder.h"
|
||||
#include "drivers/rangefinder/rangefinder_hcsr04.h"
|
||||
|
||||
|
@ -161,12 +159,10 @@ bool hcsr04Detect(rangefinderDev_t *dev, const rangefinderHardwarePins_t * range
|
|||
echoIO = IOGetByTag(rangefinderHardwarePins->echoTag);
|
||||
|
||||
if (IOGetOwner(triggerIO) != OWNER_FREE) {
|
||||
addBootlogEvent4(BOOT_EVENT_HARDWARE_IO_CONFLICT, BOOT_EVENT_FLAGS_WARNING, IOGetOwner(triggerIO), OWNER_RANGEFINDER);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (IOGetOwner(echoIO) != OWNER_FREE) {
|
||||
addBootlogEvent4(BOOT_EVENT_HARDWARE_IO_CONFLICT, BOOT_EVENT_FLAGS_WARNING, IOGetOwner(echoIO), OWNER_RANGEFINDER);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||
#if defined(USE_RX_PPM)
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
@ -38,49 +38,13 @@
|
|||
|
||||
#include "rx_pwm.h"
|
||||
|
||||
#define DEBUG_PPM_ISR
|
||||
|
||||
#define PPM_CAPTURE_COUNT 16
|
||||
#define PWM_INPUT_PORT_COUNT 8
|
||||
|
||||
#if PPM_CAPTURE_COUNT > MAX_PWM_INPUT_PORTS
|
||||
#define PWM_PORTS_OR_PPM_CAPTURE_COUNT PPM_CAPTURE_COUNT
|
||||
#else
|
||||
#define PWM_PORTS_OR_PPM_CAPTURE_COUNT PWM_INPUT_PORT_COUNT
|
||||
#endif
|
||||
|
||||
#define INPUT_FILTER_TICKS 10
|
||||
|
||||
static inputFilteringMode_e inputFilteringMode;
|
||||
#define PPM_CAPTURE_COUNT 16
|
||||
#define INPUT_FILTER_TICKS 10
|
||||
#define PPM_TIMER_PERIOD 0x10000
|
||||
|
||||
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
|
||||
|
||||
typedef enum {
|
||||
INPUT_MODE_PPM,
|
||||
INPUT_MODE_PWM,
|
||||
} pwmInputMode_t;
|
||||
|
||||
typedef struct {
|
||||
pwmInputMode_t mode;
|
||||
uint8_t channel; // only used for pwm, ignored by ppm
|
||||
|
||||
uint8_t state;
|
||||
captureCompare_t rise;
|
||||
captureCompare_t fall;
|
||||
captureCompare_t capture;
|
||||
|
||||
uint8_t missedEvents;
|
||||
|
||||
timerCallbacks_t cb;
|
||||
const TCH_t * tch;
|
||||
} pwmInputPort_t;
|
||||
|
||||
static pwmInputPort_t pwmInputPorts[PWM_INPUT_PORT_COUNT];
|
||||
|
||||
static uint16_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
|
||||
|
||||
#define PPM_TIMER_PERIOD 0x10000
|
||||
#define PWM_TIMER_PERIOD 0x10000
|
||||
static uint16_t captures[PPM_CAPTURE_COUNT];
|
||||
|
||||
static uint8_t ppmFrameCount = 0;
|
||||
static uint8_t lastPPMFrameCount = 0;
|
||||
|
@ -88,11 +52,10 @@ static uint8_t ppmCountDivisor = 1;
|
|||
|
||||
typedef struct ppmDevice_s {
|
||||
uint8_t pulseIndex;
|
||||
//uint32_t previousTime;
|
||||
uint32_t currentCapture;
|
||||
uint32_t currentTime;
|
||||
uint32_t deltaTime;
|
||||
uint32_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
|
||||
uint32_t captures[PPM_CAPTURE_COUNT];
|
||||
uint32_t largeCounter;
|
||||
int8_t numChannels;
|
||||
int8_t numChannelsPrevFrame;
|
||||
|
@ -104,14 +67,12 @@ typedef struct ppmDevice_s {
|
|||
|
||||
ppmDevice_t ppmDev;
|
||||
|
||||
|
||||
#define PPM_IN_MIN_SYNC_PULSE_US 2700 // microseconds
|
||||
#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
|
||||
#define PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
|
||||
#define PPM_IN_MIN_SYNC_PULSE_US 2700 // microseconds
|
||||
#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
|
||||
#define PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
|
||||
#define PPM_STABLE_FRAMES_REQUIRED_COUNT 25
|
||||
#define PPM_IN_MIN_NUM_CHANNELS 4
|
||||
#define PPM_IN_MAX_NUM_CHANNELS PWM_PORTS_OR_PPM_CAPTURE_COUNT
|
||||
|
||||
#define PPM_IN_MIN_NUM_CHANNELS 4
|
||||
#define PPM_IN_MAX_NUM_CHANNELS PPM_CAPTURE_COUNT
|
||||
|
||||
bool isPPMDataBeingReceived(void)
|
||||
{
|
||||
|
@ -125,36 +86,6 @@ void resetPPMDataReceivedState(void)
|
|||
|
||||
#define MIN_CHANNELS_BEFORE_PPM_FRAME_CONSIDERED_VALID 4
|
||||
|
||||
void pwmRxInit(inputFilteringMode_e inputFilteringModeToUse)
|
||||
{
|
||||
inputFilteringMode = inputFilteringModeToUse;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_PPM_ISR
|
||||
typedef enum {
|
||||
SOURCE_OVERFLOW = 0,
|
||||
SOURCE_EDGE = 1
|
||||
} eventSource_e;
|
||||
|
||||
typedef struct ppmISREvent_s {
|
||||
eventSource_e source;
|
||||
uint32_t capture;
|
||||
} ppmISREvent_t;
|
||||
|
||||
static ppmISREvent_t ppmEvents[20];
|
||||
static uint8_t ppmEventIndex = 0;
|
||||
|
||||
void ppmISREvent(eventSource_e source, uint32_t capture)
|
||||
{
|
||||
ppmEventIndex = (ppmEventIndex + 1) % (sizeof(ppmEvents) / sizeof(ppmEvents[0]));
|
||||
|
||||
ppmEvents[ppmEventIndex].source = source;
|
||||
ppmEvents[ppmEventIndex].capture = capture;
|
||||
}
|
||||
#else
|
||||
void ppmISREvent(eventSource_e source, uint32_t capture) {}
|
||||
#endif
|
||||
|
||||
static void ppmInit(void)
|
||||
{
|
||||
ppmDev.pulseIndex = 0;
|
||||
|
@ -172,7 +103,6 @@ static void ppmInit(void)
|
|||
static void ppmOverflowCallback(struct TCH_s * tch, uint32_t capture)
|
||||
{
|
||||
UNUSED(tch);
|
||||
ppmISREvent(SOURCE_OVERFLOW, capture);
|
||||
|
||||
ppmDev.largeCounter += capture + 1;
|
||||
if (capture == PPM_TIMER_PERIOD - 1) {
|
||||
|
@ -183,7 +113,6 @@ static void ppmOverflowCallback(struct TCH_s * tch, uint32_t capture)
|
|||
static void ppmEdgeCallback(struct TCH_s * tch, uint32_t capture)
|
||||
{
|
||||
UNUSED(tch);
|
||||
ppmISREvent(SOURCE_EDGE, capture);
|
||||
|
||||
int32_t i;
|
||||
|
||||
|
@ -219,7 +148,7 @@ static void ppmEdgeCallback(struct TCH_s * tch, uint32_t capture)
|
|||
ppmDev.currentTime = currentTime;
|
||||
ppmDev.currentCapture = capture;
|
||||
|
||||
#if 1
|
||||
#if 0
|
||||
static uint32_t deltaTimes[20];
|
||||
static uint8_t deltaIndex = 0;
|
||||
|
||||
|
@ -229,7 +158,7 @@ static void ppmEdgeCallback(struct TCH_s * tch, uint32_t capture)
|
|||
#endif
|
||||
|
||||
|
||||
#if 1
|
||||
#if 0
|
||||
static uint32_t captureTimes[20];
|
||||
static uint8_t captureIndex = 0;
|
||||
|
||||
|
@ -282,123 +211,38 @@ static void ppmEdgeCallback(struct TCH_s * tch, uint32_t capture)
|
|||
} else {
|
||||
/* Not a valid pulse duration */
|
||||
ppmDev.tracking = false;
|
||||
for (i = 0; i < PWM_PORTS_OR_PPM_CAPTURE_COUNT; i++) {
|
||||
for (i = 0; i < PPM_CAPTURE_COUNT; i++) {
|
||||
ppmDev.captures[i] = PPM_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#define MAX_MISSED_PWM_EVENTS 10
|
||||
|
||||
bool isPWMDataBeingReceived(void)
|
||||
bool ppmInConfig(const timerHardware_t *timerHardwarePtr)
|
||||
{
|
||||
int channel;
|
||||
for (channel = 0; channel < PWM_PORTS_OR_PPM_CAPTURE_COUNT; channel++) {
|
||||
if (captures[channel] != PPM_RCVR_TIMEOUT) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static void pwmOverflowCallback(struct TCH_s * tch, uint32_t capture)
|
||||
{
|
||||
UNUSED(capture);
|
||||
pwmInputPort_t *pwmInputPort = (pwmInputPort_t *)tch->cb->callbackParam;
|
||||
|
||||
if (++pwmInputPort->missedEvents > MAX_MISSED_PWM_EVENTS) {
|
||||
captures[pwmInputPort->channel] = PPM_RCVR_TIMEOUT;
|
||||
pwmInputPort->missedEvents = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void pwmEdgeCallback(struct TCH_s * tch, uint32_t capture)
|
||||
{
|
||||
pwmInputPort_t *pwmInputPort = (pwmInputPort_t *)tch->cb->callbackParam;
|
||||
|
||||
if (pwmInputPort->state == 0) {
|
||||
pwmInputPort->rise = capture;
|
||||
pwmInputPort->state = 1;
|
||||
timerChConfigIC(tch, false, INPUT_FILTER_TICKS);
|
||||
} else {
|
||||
pwmInputPort->fall = capture;
|
||||
|
||||
// compute and store capture and handle overflow correctly - timer may be configured for PWM output in such case overflow value is not 0xFFFF
|
||||
if (pwmInputPort->fall >= pwmInputPort->rise) {
|
||||
pwmInputPort->capture = pwmInputPort->fall - pwmInputPort->rise;
|
||||
}
|
||||
else {
|
||||
pwmInputPort->capture = (pwmInputPort->fall + timerGetPeriod(tch)) - pwmInputPort->rise;
|
||||
}
|
||||
captures[pwmInputPort->channel] = pwmInputPort->capture;
|
||||
|
||||
// switch state
|
||||
pwmInputPort->state = 0;
|
||||
timerChConfigIC(tch, true, INPUT_FILTER_TICKS);
|
||||
pwmInputPort->missedEvents = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
|
||||
{
|
||||
pwmInputPort_t *self = &pwmInputPorts[channel];
|
||||
|
||||
static timerCallbacks_t callbacks;
|
||||
TCH_t * tch = timerGetTCH(timerHardwarePtr);
|
||||
if (tch == NULL) {
|
||||
return;
|
||||
}
|
||||
|
||||
self->state = 0;
|
||||
self->missedEvents = 0;
|
||||
self->channel = channel;
|
||||
self->mode = INPUT_MODE_PWM;
|
||||
|
||||
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
||||
IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
|
||||
IOConfigGPIOAF(io, timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
|
||||
|
||||
timerConfigure(tch, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_HZ);
|
||||
timerChInitCallbacks(&self->cb, (void*)self, &pwmEdgeCallback, &pwmOverflowCallback);
|
||||
timerChConfigCallbacks(tch, &self->cb);
|
||||
timerChConfigIC(tch, true, INPUT_FILTER_TICKS);
|
||||
timerChCaptureEnable(tch);
|
||||
}
|
||||
|
||||
#define UNUSED_PPM_TIMER_REFERENCE 0
|
||||
#define FIRST_PWM_PORT 0
|
||||
|
||||
void ppmInConfig(const timerHardware_t *timerHardwarePtr)
|
||||
{
|
||||
TCH_t * tch = timerGetTCH(timerHardwarePtr);
|
||||
if (tch == NULL) {
|
||||
return;
|
||||
return false;
|
||||
}
|
||||
|
||||
ppmInit();
|
||||
|
||||
pwmInputPort_t *self = &pwmInputPorts[FIRST_PWM_PORT];
|
||||
|
||||
self->mode = INPUT_MODE_PPM;
|
||||
|
||||
IO_t io = IOGetByTag(timerHardwarePtr->tag);
|
||||
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIOAF(io, timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
|
||||
|
||||
timerConfigure(tch, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_HZ);
|
||||
timerChInitCallbacks(&self->cb, (void*)self, &ppmEdgeCallback, &ppmOverflowCallback);
|
||||
timerChConfigCallbacks(tch, &self->cb);
|
||||
timerChInitCallbacks(&callbacks, (void*)&ppmDev, &ppmEdgeCallback, &ppmOverflowCallback);
|
||||
timerChConfigCallbacks(tch, &callbacks);
|
||||
timerChConfigIC(tch, true, INPUT_FILTER_TICKS);
|
||||
timerChCaptureEnable(tch);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t ppmRead(uint8_t channel)
|
||||
{
|
||||
return captures[channel];
|
||||
}
|
||||
|
||||
uint16_t pwmRead(uint8_t channel)
|
||||
{
|
||||
return captures[channel];
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -17,15 +17,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
typedef enum {
|
||||
INPUT_FILTERING_DISABLED = 0,
|
||||
INPUT_FILTERING_ENABLED
|
||||
} inputFilteringMode_e;
|
||||
|
||||
#define PPM_RCVR_TIMEOUT 0
|
||||
|
||||
struct timerHardware_s;
|
||||
void ppmInConfig(const struct timerHardware_s *timerHardwarePtr);
|
||||
bool ppmInConfig(const struct timerHardware_s *timerHardwarePtr);
|
||||
|
||||
void pwmInConfig(const struct timerHardware_s *timerHardwarePtr, uint8_t channel);
|
||||
uint16_t pwmRead(uint8_t channel);
|
||||
|
@ -34,6 +29,4 @@ uint16_t ppmRead(uint8_t channel);
|
|||
bool isPPMDataBeingReceived(void);
|
||||
void resetPPMDataReceivedState(void);
|
||||
|
||||
void pwmRxInit(inputFilteringMode_e inputFilteringMode);
|
||||
|
||||
bool isPWMDataBeingReceived(void);
|
||||
|
|
|
@ -16,6 +16,12 @@
|
|||
*/
|
||||
|
||||
#pragma once
|
||||
#include "drivers/io.h"
|
||||
|
||||
typedef struct {
|
||||
ioTag_t rxPin;
|
||||
ioTag_t txPin;
|
||||
} serialPortPins_t;
|
||||
|
||||
typedef enum portMode_t {
|
||||
MODE_RX = 1 << 0,
|
||||
|
|
|
@ -61,6 +61,7 @@ typedef struct {
|
|||
USART_TypeDef *USARTx;
|
||||
} uartPort_t;
|
||||
|
||||
void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins);
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
|
||||
// serialPort API
|
||||
|
|
|
@ -98,6 +98,47 @@ static uartPort_t uartPort4;
|
|||
static uartPort_t uartPort5;
|
||||
#endif
|
||||
|
||||
|
||||
void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins)
|
||||
{
|
||||
switch(device) {
|
||||
#ifdef USE_UART1
|
||||
case UARTDEV_1:
|
||||
pins->txPin = IO_TAG(UART1_TX_PIN);
|
||||
pins->rxPin = IO_TAG(UART1_RX_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_UART2
|
||||
case UARTDEV_2:
|
||||
pins->txPin = IO_TAG(UART2_TX_PIN);
|
||||
pins->rxPin = IO_TAG(UART2_RX_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_UART3
|
||||
case UARTDEV_3:
|
||||
pins->txPin = IO_TAG(UART3_TX_PIN);
|
||||
pins->rxPin = IO_TAG(UART3_RX_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_UART4
|
||||
case UARTDEV_4:
|
||||
pins->txPin = IO_TAG(UART4_TX_PIN);
|
||||
pins->rxPin = IO_TAG(UART4_RX_PIN);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_UART5
|
||||
case UARTDEV_5:
|
||||
pins->txPin = IO_TAG(UART5_TX_PIN);
|
||||
pins->rxPin = IO_TAG(UART5_RX_PIN);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
pins->txPin = IO_TAG(NONE);
|
||||
pins->rxPin = IO_TAG(NONE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index)
|
||||
{
|
||||
if (options & SERIAL_BIDIR) {
|
||||
|
|
|
@ -239,6 +239,20 @@ void uartIrqHandler(uartPort_t *s)
|
|||
}
|
||||
}
|
||||
|
||||
void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins)
|
||||
{
|
||||
uartDevice_t *uart = uartHardwareMap[device];
|
||||
|
||||
if (uart) {
|
||||
pins->txPin = uart->tx;
|
||||
pins->rxPin = uart->rx;
|
||||
}
|
||||
else {
|
||||
pins->txPin = IO_TAG(NONE);
|
||||
pins->rxPin = IO_TAG(NONE);
|
||||
}
|
||||
}
|
||||
|
||||
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
|
|
|
@ -286,6 +286,20 @@ void uartIrqHandler(uartPort_t *s)
|
|||
}
|
||||
}
|
||||
|
||||
void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins)
|
||||
{
|
||||
uartDevice_t *uart = uartHardwareMap[device];
|
||||
|
||||
if (uart) {
|
||||
pins->txPin = uart->tx;
|
||||
pins->rxPin = uart->rx;
|
||||
}
|
||||
else {
|
||||
pins->txPin = IO_TAG(NONE);
|
||||
pins->rxPin = IO_TAG(NONE);
|
||||
}
|
||||
}
|
||||
|
||||
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
|
|
|
@ -193,6 +193,16 @@ const timerHardware_t * timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
const timerHardware_t * timerGetByUsageFlag(timerUsageFlag_e flag)
|
||||
{
|
||||
for (int i = 0; i < timerHardwareCount; i++) {
|
||||
if (timerHardware[i].usageFlags & flag) {
|
||||
return &timerHardware[i];
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void timerPWMConfigChannel(TCH_t * tch, uint16_t value)
|
||||
{
|
||||
impl_timerPWMConfigChannel(tch, value);
|
||||
|
|
|
@ -168,6 +168,7 @@ typedef enum {
|
|||
uint8_t timerClockDivisor(TIM_TypeDef *tim);
|
||||
uint32_t timerGetBaseClockHW(const timerHardware_t * timHw);
|
||||
|
||||
const timerHardware_t * timerGetByUsageFlag(timerUsageFlag_e flag);
|
||||
const timerHardware_t * timerGetByTag(ioTag_t tag, timerUsageFlag_e flag);
|
||||
TCH_t * timerGetTCH(const timerHardware_t * timHw);
|
||||
|
||||
|
|
|
@ -50,12 +50,12 @@ extern uint8_t __config_end;
|
|||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/osd_symbols.h"
|
||||
#include "drivers/rx_pwm.h"
|
||||
#include "drivers/sdcard.h"
|
||||
|
@ -135,10 +135,6 @@ static uint32_t bufferIndex = 0;
|
|||
static void cliAssert(char *cmdline);
|
||||
#endif
|
||||
|
||||
#if defined(USE_BOOTLOG)
|
||||
static void cliBootlog(char *cmdline);
|
||||
#endif
|
||||
|
||||
// sync this with features_e
|
||||
static const char * const featureNames[] = {
|
||||
"THR_VBAT_COMP", "VBAT", "TX_PROF_SEL", "BAT_PROF_AUTOSWITCH", "MOTOR_STOP",
|
||||
|
@ -580,46 +576,6 @@ static void cliAssert(char *cmdline)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_BOOTLOG)
|
||||
static void cliBootlog(char *cmdline)
|
||||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
int bootEventCount = getBootlogEventCount();
|
||||
|
||||
#if defined(BOOTLOG_DESCRIPTIONS)
|
||||
cliPrintLine("Time Evt Description Parameters");
|
||||
#else
|
||||
cliPrintLine("Time Evt Parameters");
|
||||
#endif
|
||||
|
||||
for (int idx = 0; idx < bootEventCount; idx++) {
|
||||
bootLogEntry_t * event = getBootlogEvent(idx);
|
||||
|
||||
#if defined(BOOTLOG_DESCRIPTIONS)
|
||||
const char * eventDescription = getBootlogEventDescription(event->eventCode);
|
||||
if (!eventDescription) {
|
||||
eventDescription = "";
|
||||
}
|
||||
|
||||
cliPrintf("%4d: %2d %22s ", event->timestamp, event->eventCode, eventDescription);
|
||||
#else
|
||||
cliPrintf("%4d: %2d ", event->timestamp, event->eventCode);
|
||||
#endif
|
||||
|
||||
if (event->eventFlags & BOOT_EVENT_FLAGS_PARAM16) {
|
||||
cliPrintLinef(" (%d, %d, %d, %d)", event->params.u16[0], event->params.u16[1], event->params.u16[2], event->params.u16[3]);
|
||||
}
|
||||
else if (event->eventFlags & BOOT_EVENT_FLAGS_PARAM32) {
|
||||
cliPrintLinef(" (%d, %d)", event->params.u32[0], event->params.u32[1]);
|
||||
}
|
||||
else {
|
||||
cliPrintLinefeed();
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static void printAux(uint8_t dumpMask, const modeActivationCondition_t *modeActivationConditions, const modeActivationCondition_t *defaultModeActivationConditions)
|
||||
{
|
||||
const char *format = "aux %u %u %u %u %u";
|
||||
|
@ -2816,6 +2772,11 @@ static void cliStatus(char *cmdline)
|
|||
#else
|
||||
cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS);
|
||||
#endif
|
||||
|
||||
// If we are blocked by PWM init - provide more information
|
||||
if (getPwmInitError() != PWM_INIT_ERROR_NONE) {
|
||||
cliPrintLinef("PWM output init error: %s", getPwmInitErrorMessage());
|
||||
}
|
||||
}
|
||||
|
||||
#ifndef SKIP_TASK_STATISTICS
|
||||
|
|
|
@ -38,6 +38,7 @@
|
|||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/timer.h"
|
||||
|
@ -106,7 +107,7 @@ PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
|||
.enabledFeatures = DEFAULT_FEATURES | COMMON_DEFAULT_FEATURES
|
||||
);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 3);
|
||||
|
||||
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||
.current_profile_index = 0,
|
||||
|
@ -115,7 +116,6 @@ PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
|||
.i2c_speed = I2C_SPEED_400KHZ,
|
||||
.cpuUnderclock = 0,
|
||||
.throttle_tilt_compensation_strength = 0, // 0-100, 0 - disabled
|
||||
.pwmRxInputFilteringMode = INPUT_FILTERING_DISABLED,
|
||||
.name = { 0 }
|
||||
);
|
||||
|
||||
|
|
|
@ -76,7 +76,6 @@ typedef struct systemConfig_s {
|
|||
uint8_t i2c_speed;
|
||||
uint8_t cpuUnderclock;
|
||||
uint8_t throttle_tilt_compensation_strength; // the correction that will be applied at throttle_correction_angle.
|
||||
inputFilteringMode_e pwmRxInputFilteringMode;
|
||||
char name[MAX_NAME_LENGTH + 1];
|
||||
} systemConfig_t;
|
||||
|
||||
|
|
|
@ -54,7 +54,6 @@
|
|||
#include "drivers/io.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/osd.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
|
@ -180,8 +179,6 @@ void init(void)
|
|||
#endif
|
||||
|
||||
systemState = SYSTEM_STATE_INITIALISING;
|
||||
initBootlog();
|
||||
|
||||
printfSupportInit();
|
||||
|
||||
// Initialize system and CPU clocks to their initial values
|
||||
|
@ -211,7 +208,6 @@ void init(void)
|
|||
initialisePreBootHardware();
|
||||
#endif
|
||||
|
||||
addBootlogEvent2(BOOT_EVENT_CONFIG_LOADED, BOOT_EVENT_FLAGS_NONE);
|
||||
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
||||
|
||||
debugMode = systemConfig()->debug_mode;
|
||||
|
@ -229,8 +225,6 @@ void init(void)
|
|||
EXTIInit();
|
||||
#endif
|
||||
|
||||
addBootlogEvent2(BOOT_EVENT_SYSTEM_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
|
||||
|
||||
#ifdef USE_SPEKTRUM_BIND
|
||||
if (rxConfig()->receiverType == RX_TYPE_SERIAL) {
|
||||
switch (rxConfig()->serialrx_provider) {
|
||||
|
@ -273,43 +267,33 @@ void init(void)
|
|||
logInit();
|
||||
#endif
|
||||
|
||||
// Initialize servo and motor mixers
|
||||
// This needs to be called early to set up platform type correctly and count required motors & servos
|
||||
servosInit();
|
||||
mixerUpdateStateFlags(); // This needs to be called early to allow pwm mapper to use information about FIXED_WING state
|
||||
mixerUpdateStateFlags();
|
||||
mixerInit();
|
||||
|
||||
// Some sanity checking
|
||||
if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||
featureClear(FEATURE_3D);
|
||||
}
|
||||
|
||||
// Initialize motor and servo outpus
|
||||
if (pwmMotorAndServoInit()) {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR);
|
||||
}
|
||||
else {
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR);
|
||||
}
|
||||
|
||||
/*
|
||||
drv_pwm_config_t pwm_params;
|
||||
memset(&pwm_params, 0, sizeof(pwm_params));
|
||||
|
||||
#ifdef USE_RANGEFINDER_HCSR04
|
||||
// HC-SR04 has a dedicated connection to FC and require two pins
|
||||
if (rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) {
|
||||
const rangefinderHardwarePins_t *rangefinderHardwarePins = rangefinderGetHardwarePins();
|
||||
if (rangefinderHardwarePins) {
|
||||
pwm_params.useTriggerRangefinder = true;
|
||||
pwm_params.rangefinderIOConfig.triggerTag = rangefinderHardwarePins->triggerTag;
|
||||
pwm_params.rangefinderIOConfig.echoTag = rangefinderHardwarePins->echoTag;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||
pwm_params.flyingPlatformType = mixerConfig()->platformType;
|
||||
|
||||
#ifdef STM32F303xC
|
||||
pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3);
|
||||
#endif
|
||||
#if defined(USE_UART2) && defined(STM32F40_41xxx)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
#endif
|
||||
#if defined(USE_UART6) && defined(STM32F40_41xxx)
|
||||
pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6);
|
||||
#endif
|
||||
pwm_params.useVbat = feature(FEATURE_VBAT);
|
||||
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
|
||||
pwm_params.useParallelPWM = (rxConfig()->receiverType == RX_TYPE_PWM);
|
||||
pwm_params.useRSSIADC = feature(FEATURE_RSSI_ADC);
|
||||
pwm_params.useCurrentMeterADC = feature(FEATURE_CURRENT_METER)
|
||||
&& batteryMetersConfig()->current.type == CURRENT_SENSOR_ADC;
|
||||
pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
|
||||
pwm_params.usePPM = (rxConfig()->receiverType == RX_TYPE_PPM);
|
||||
pwm_params.useSerialRx = (rxConfig()->receiverType == RX_TYPE_SERIAL);
|
||||
|
||||
|
@ -317,9 +301,6 @@ void init(void)
|
|||
pwm_params.servoCenterPulse = servoConfig()->servoCenterPulse;
|
||||
pwm_params.servoPwmRate = servoConfig()->servoPwmRate;
|
||||
|
||||
if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||
featureClear(FEATURE_3D);
|
||||
}
|
||||
|
||||
pwm_params.enablePWMOutput = feature(FEATURE_PWM_OUTPUT_ENABLE);
|
||||
|
||||
|
@ -328,21 +309,14 @@ void init(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
/*
|
||||
If external PWM driver is enabled, for example PCA9685, disable internal
|
||||
servo handling mechanism, since external device will do that
|
||||
*/
|
||||
// If external PWM driver is enabled, for example PCA9685, disable internal
|
||||
// servo handling mechanism, since external device will do that
|
||||
if (feature(FEATURE_PWM_SERVO_DRIVER)) {
|
||||
pwm_params.useServoOutputs = false;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
|
||||
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
|
||||
pwmInit(&pwm_params);
|
||||
|
||||
mixerPrepare();
|
||||
|
||||
addBootlogEvent2(BOOT_EVENT_PWM_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
|
||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||
|
||||
#ifdef BEEPER
|
||||
|
@ -467,8 +441,6 @@ void init(void)
|
|||
|
||||
/* Extra 500ms delay prior to initialising hardware if board is cold-booting */
|
||||
if (!isMPUSoftReset()) {
|
||||
addBootlogEvent2(BOOT_EVENT_EXTRA_BOOT_DELAY, BOOT_EVENT_FLAGS_NONE);
|
||||
|
||||
LED1_ON;
|
||||
LED0_OFF;
|
||||
|
||||
|
@ -511,7 +483,6 @@ void init(void)
|
|||
failureMode(FAILURE_MISSING_ACC);
|
||||
}
|
||||
|
||||
addBootlogEvent2(BOOT_EVENT_SENSOR_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
|
||||
systemState |= SYSTEM_STATE_SENSORS_READY;
|
||||
|
||||
flashLedsAndBeep();
|
||||
|
@ -561,7 +532,6 @@ void init(void)
|
|||
#ifdef USE_GPS
|
||||
if (feature(FEATURE_GPS)) {
|
||||
gpsInit();
|
||||
addBootlogEvent2(BOOT_EVENT_GPS_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -575,14 +545,12 @@ void init(void)
|
|||
|
||||
if (feature(FEATURE_LED_STRIP)) {
|
||||
ledStripEnable();
|
||||
addBootlogEvent2(BOOT_EVENT_LEDSTRIP_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_TELEMETRY
|
||||
if (feature(FEATURE_TELEMETRY)) {
|
||||
telemetryInit();
|
||||
addBootlogEvent2(BOOT_EVENT_TELEMETRY_INIT_DONE, BOOT_EVENT_FLAGS_NONE);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -661,6 +629,5 @@ void init(void)
|
|||
motorControlEnable = true;
|
||||
fcTasksInit();
|
||||
|
||||
addBootlogEvent2(BOOT_EVENT_SYSTEM_READY, BOOT_EVENT_FLAGS_NONE);
|
||||
systemState |= SYSTEM_STATE_READY;
|
||||
}
|
||||
|
|
|
@ -35,7 +35,7 @@ const char *armingDisableFlagNames[]= {
|
|||
"FS", "ANGLE", "CAL", "OVRLD", "NAV", "COMPASS",
|
||||
"ACC", "ARMSW", "HWFAIL", "BOXFS", "KILLSW", "RX",
|
||||
"THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM",
|
||||
"SETTINGFAIL",
|
||||
"SETTINGFAIL", "PWMOUT"
|
||||
};
|
||||
#endif
|
||||
|
||||
|
|
|
@ -39,16 +39,20 @@ typedef enum {
|
|||
ARMING_DISABLED_CLI = (1 << 20),
|
||||
ARMING_DISABLED_CMS_MENU = (1 << 21),
|
||||
ARMING_DISABLED_OSD_MENU = (1 << 22),
|
||||
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED = (1 << 23),
|
||||
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED = (1 << 23),
|
||||
ARMING_DISABLED_SERVO_AUTOTRIM = (1 << 24),
|
||||
ARMING_DISABLED_OOM = (1 << 25),
|
||||
ARMING_DISABLED_INVALID_SETTING = (1 << 26),
|
||||
ARMING_DISABLED_PWM_OUTPUT_ERROR = (1 << 27),
|
||||
|
||||
ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED |
|
||||
ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED |
|
||||
ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_BOXKILLSWITCH |
|
||||
ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU |
|
||||
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING)
|
||||
ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING |
|
||||
ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE |
|
||||
ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED |
|
||||
ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE |
|
||||
ARMING_DISABLED_BOXKILLSWITCH | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI |
|
||||
ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED |
|
||||
ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING |
|
||||
ARMING_DISABLED_PWM_OUTPUT_ERROR)
|
||||
} armingFlag_e;
|
||||
|
||||
extern uint32_t armingFlags;
|
||||
|
|
|
@ -77,7 +77,7 @@ tables:
|
|||
- name: debug_modes
|
||||
values: ["NONE", "GYRO", "NOTCH", "NAV_LANDING", "FW_ALTITUDE", "AGL", "FLOW_RAW",
|
||||
"FLOW", "SBUS", "FPORT", "ALWAYS", "STAGE2", "SAG_COMP_VOLTAGE",
|
||||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "GENERIC", "ITERM_RELAX"]
|
||||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "GENERIC", "ITERM_RELAX", "D_BOOST"]
|
||||
- name: async_mode
|
||||
values: ["NONE", "GYRO", "ALL"]
|
||||
- name: aux_operator
|
||||
|
@ -1136,6 +1136,21 @@ groups:
|
|||
field: iterm_relax_cutoff
|
||||
min: 1
|
||||
max: 100
|
||||
- name: d_boost_factor
|
||||
field: dBoostFactor
|
||||
condition: USE_D_BOOST
|
||||
min: 1
|
||||
max: 3
|
||||
- name: d_boost_max_at_acceleration
|
||||
field: dBoostMaxAtAlleceleration
|
||||
condition: USE_D_BOOST
|
||||
min: 1000
|
||||
max: 16000
|
||||
- name: d_boost_gyro_delta_lpf_hz
|
||||
field: dBoostGyroDeltaLpfHz
|
||||
condition: USE_D_BOOST
|
||||
min: 10
|
||||
max: 250
|
||||
|
||||
- name: PG_PID_AUTOTUNE_CONFIG
|
||||
type: pidAutotuneConfig_t
|
||||
|
@ -1737,9 +1752,6 @@ groups:
|
|||
field: throttle_tilt_compensation_strength
|
||||
min: 0
|
||||
max: 100
|
||||
- name: input_filtering_mode
|
||||
field: pwmRxInputFilteringMode
|
||||
type: bool
|
||||
- name: name
|
||||
|
||||
- name: PG_MODE_ACTIVATION_OPERATOR_CONFIG
|
||||
|
|
|
@ -148,7 +148,7 @@ void mixerUpdateStateFlags(void)
|
|||
}
|
||||
}
|
||||
|
||||
void mixerPrepare(void)
|
||||
void mixerInit(void)
|
||||
{
|
||||
computeMotorCount();
|
||||
loadPrimaryMotorMixer();
|
||||
|
|
|
@ -110,7 +110,7 @@ bool mixerIsOutputSaturated(void);
|
|||
motorStatus_e getMotorStatus(void);
|
||||
|
||||
void writeAllMotors(int16_t mc);
|
||||
void mixerPrepare(void);
|
||||
void mixerInit(void);
|
||||
void mixerUpdateStateFlags(void);
|
||||
void mixerResetDisarmedMotors(void);
|
||||
void mixTable(const float dT);
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
@ -86,6 +87,13 @@ typedef struct {
|
|||
biquadFilter_t deltaNotchFilter;
|
||||
#endif
|
||||
float stickPosition;
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
float previousRateTarget;
|
||||
float previousRateGyro;
|
||||
pt1Filter_t dBoostLpf;
|
||||
biquadFilter_t dBoostGyroLpf;
|
||||
#endif
|
||||
} pidState_t;
|
||||
|
||||
#ifdef USE_DTERM_NOTCH
|
||||
|
@ -115,7 +123,15 @@ static EXTENDED_FASTRAM uint8_t itermRelax;
|
|||
static EXTENDED_FASTRAM uint8_t itermRelaxType;
|
||||
static EXTENDED_FASTRAM float itermRelaxSetpointThreshold;
|
||||
|
||||
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 8);
|
||||
#define D_BOOST_GYRO_LPF_HZ 80 // Biquad lowpass input cutoff to peak D around propwash frequencies
|
||||
#define D_BOOST_LPF_HZ 10 // PT1 lowpass cutoff to smooth the boost effect
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
static EXTENDED_FASTRAM float dBoostFactor;
|
||||
static EXTENDED_FASTRAM float dBoostMaxAtAlleceleration;
|
||||
#endif
|
||||
|
||||
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 9);
|
||||
|
||||
PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
||||
.bank_mc = {
|
||||
|
@ -214,6 +230,9 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
.iterm_relax_type = ITERM_RELAX_SETPOINT,
|
||||
.iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT,
|
||||
.iterm_relax = ITERM_RELAX_OFF,
|
||||
.dBoostFactor = 1.0f,
|
||||
.dBoostMaxAtAlleceleration = 7500.0f,
|
||||
.dBoostGyroDeltaLpfHz = D_BOOST_GYRO_LPF_HZ,
|
||||
);
|
||||
|
||||
void pidInit(void)
|
||||
|
@ -229,6 +248,12 @@ void pidInit(void)
|
|||
itermRelax = pidProfile()->iterm_relax;
|
||||
itermRelaxType = pidProfile()->iterm_relax_type;
|
||||
itermRelaxSetpointThreshold = MC_ITERM_RELAX_SETPOINT_THRESHOLD * MC_ITERM_RELAX_CUTOFF_DEFAULT / pidProfile()->iterm_relax_cutoff;
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
dBoostFactor = pidProfile()->dBoostFactor;
|
||||
dBoostMaxAtAlleceleration = pidProfile()->dBoostMaxAtAlleceleration;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
bool pidInitFilters(void)
|
||||
|
@ -282,6 +307,12 @@ bool pidInitFilters(void)
|
|||
pt1FilterInit(&windupLpf[i], pidProfile()->iterm_relax_cutoff, refreshRate * 1e-6f);
|
||||
}
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
biquadFilterInitLPF(&pidState[axis].dBoostGyroLpf, pidProfile()->dBoostGyroDeltaLpfHz, getLooptime());
|
||||
}
|
||||
#endif
|
||||
|
||||
pidFiltersConfigured = true;
|
||||
|
||||
return true;
|
||||
|
@ -594,6 +625,42 @@ static void FAST_CODE applyItermRelax(const int axis, const float gyroRate, floa
|
|||
}
|
||||
}
|
||||
}
|
||||
#ifdef USE_D_BOOST
|
||||
static float FAST_CODE applyDBoost(pidState_t *pidState, flight_dynamics_index_t axis) {
|
||||
|
||||
float dBoost = 1.0f;
|
||||
|
||||
if (dBoostFactor > 1) {
|
||||
const float dBoostGyroDelta = (pidState->gyroRate - pidState->previousRateGyro) / dT;
|
||||
const float dBoostGyroAcceleration = fabsf(biquadFilterApply(&pidState->dBoostGyroLpf, dBoostGyroDelta));
|
||||
const float dBoostRateAcceleration = fabsf((pidState->rateTarget - pidState->previousRateTarget) / dT);
|
||||
|
||||
const float acceleration = MAX(dBoostGyroAcceleration, dBoostRateAcceleration);
|
||||
dBoost = scaleRangef(acceleration, 0.0f, dBoostMaxAtAlleceleration, 1.0f, dBoostFactor);
|
||||
dBoost = pt1FilterApply4(&pidState->dBoostLpf, dBoost, D_BOOST_LPF_HZ, dT);
|
||||
dBoost = constrainf(dBoost, 1.0f, dBoostFactor);
|
||||
|
||||
if (axis == FD_ROLL) {
|
||||
DEBUG_SET(DEBUG_D_BOOST, 0, dBoostGyroAcceleration);
|
||||
DEBUG_SET(DEBUG_D_BOOST, 1, dBoostRateAcceleration);
|
||||
DEBUG_SET(DEBUG_D_BOOST, 2, dBoost * 100);
|
||||
} else if (axis == FD_PITCH) {
|
||||
DEBUG_SET(DEBUG_D_BOOST, 3, dBoost * 100);
|
||||
}
|
||||
|
||||
pidState->previousRateTarget = pidState->rateTarget;
|
||||
pidState->previousRateGyro = pidState->gyroRate;
|
||||
}
|
||||
|
||||
return dBoost;
|
||||
}
|
||||
#else
|
||||
static float applyDBoost(pidState_t *pidState, flight_dynamics_index_t axis) {
|
||||
UNUSED(pidState);
|
||||
UNUSED(axis);
|
||||
return 1.0f;
|
||||
}
|
||||
#endif
|
||||
|
||||
static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, flight_dynamics_index_t axis)
|
||||
{
|
||||
|
@ -634,7 +701,7 @@ static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, fl
|
|||
newDTerm = firFilterApply(&pidState->gyroRateFilter);
|
||||
|
||||
// Calculate derivative
|
||||
newDTerm = newDTerm * (pidState->kD / dT);
|
||||
newDTerm = newDTerm * (pidState->kD / dT) * applyDBoost(pidState, axis);
|
||||
|
||||
// Additionally constrain D
|
||||
newDTerm = constrainf(newDTerm, -300.0f, 300.0f);
|
||||
|
|
|
@ -127,6 +127,10 @@ typedef struct pidProfile_s {
|
|||
uint8_t iterm_relax_type; // Specifies type of relax algorithm
|
||||
uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
|
||||
uint8_t iterm_relax; // Enable iterm suppression during stick input
|
||||
|
||||
float dBoostFactor;
|
||||
float dBoostMaxAtAlleceleration;
|
||||
uint8_t dBoostGyroDeltaLpfHz;
|
||||
} pidProfile_t;
|
||||
|
||||
typedef struct pidAutotuneConfig_s {
|
||||
|
|
|
@ -144,9 +144,19 @@ void servosInit(void)
|
|||
mixerUsesServos = 1;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++)
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servoComputeScalingFactors(i);
|
||||
}
|
||||
}
|
||||
|
||||
int getServoCount(void)
|
||||
{
|
||||
if (servoRuleCount) {
|
||||
return 1 + maxServoIndex - minServoIndex;
|
||||
}
|
||||
else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void loadCustomServoMixer(void)
|
||||
|
|
|
@ -149,3 +149,4 @@ void loadCustomServoMixer(void);
|
|||
void servoMixer(float dT);
|
||||
void servoComputeScalingFactors(uint8_t servoIndex);
|
||||
void servosInit(void);
|
||||
int getServoCount(void);
|
||||
|
|
|
@ -296,20 +296,22 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist)
|
|||
{
|
||||
switch ((osd_unit_e)osdConfig()->units) {
|
||||
case OSD_UNIT_IMPERIAL:
|
||||
if (osdFormatCentiNumber(buff + 1, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, 0, 3, 3)) {
|
||||
buff[0] = SYM_DIST_MI;
|
||||
if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, 0, 3, 3)) {
|
||||
buff[3] = SYM_DIST_MI;
|
||||
} else {
|
||||
buff[0] = SYM_DIST_FT;
|
||||
buff[3] = SYM_DIST_FT;
|
||||
}
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
case OSD_UNIT_UK:
|
||||
FALLTHROUGH;
|
||||
case OSD_UNIT_METRIC:
|
||||
if (osdFormatCentiNumber(buff + 1, dist, METERS_PER_KILOMETER, 0, 3, 3)) {
|
||||
buff[0] = SYM_DIST_KM;
|
||||
if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, 0, 3, 3)) {
|
||||
buff[3] = SYM_DIST_KM;
|
||||
} else {
|
||||
buff[0] = SYM_DIST_M;
|
||||
buff[3] = SYM_DIST_M;
|
||||
}
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -428,23 +430,25 @@ static void osdFormatAltitudeSymbol(char *buff, int32_t alt)
|
|||
case OSD_UNIT_UK:
|
||||
FALLTHROUGH;
|
||||
case OSD_UNIT_IMPERIAL:
|
||||
if (osdFormatCentiNumber(buff + 1, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, 3)) {
|
||||
if (osdFormatCentiNumber(buff , CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, 3)) {
|
||||
// Scaled to kft
|
||||
buff[0] = SYM_ALT_KFT;
|
||||
buff[3] = SYM_ALT_KFT;
|
||||
} else {
|
||||
// Formatted in feet
|
||||
buff[0] = SYM_ALT_FT;
|
||||
buff[3] = SYM_ALT_FT;
|
||||
}
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
case OSD_UNIT_METRIC:
|
||||
// alt is alredy in cm
|
||||
if (osdFormatCentiNumber(buff+1, alt, 1000, 0, 2, 3)) {
|
||||
if (osdFormatCentiNumber(buff, alt, 1000, 0, 2, 3)) {
|
||||
// Scaled to km
|
||||
buff[0] = SYM_ALT_KM;
|
||||
buff[3] = SYM_ALT_KM;
|
||||
} else {
|
||||
// Formatted in m
|
||||
buff[0] = SYM_ALT_M;
|
||||
buff[3] = SYM_ALT_M;
|
||||
}
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -681,6 +685,8 @@ static const char * osdArmingDisabledReasonMessage(void)
|
|||
return OSD_MESSAGE_STR("INVALID SETTING");
|
||||
case ARMING_DISABLED_CLI:
|
||||
return OSD_MESSAGE_STR("CLI IS ACTIVE");
|
||||
case ARMING_DISABLED_PWM_OUTPUT_ERROR:
|
||||
return OSD_MESSAGE_STR("PWM INIT ERROR");
|
||||
// Cases without message
|
||||
case ARMING_DISABLED_CMS_MENU:
|
||||
FALLTHROUGH;
|
||||
|
@ -1165,8 +1171,10 @@ static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_
|
|||
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr);
|
||||
|
||||
elemAttr = TEXT_ATTRIBUTES_NONE;
|
||||
osdFormatCentiNumber(buff, voltage, 0, decimals, 0, MIN(digits, 4));
|
||||
strcat(buff, "V");
|
||||
digits = MIN(digits, 4);
|
||||
osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits);
|
||||
buff[digits] = SYM_VOLT;
|
||||
buff[digits+1] = '\0';
|
||||
if ((getBatteryState() != BATTERY_NOT_PRESENT) && (getBatteryVoltage() <= getBatteryWarningVoltage()))
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 1, elemPosY, buff, elemAttr);
|
||||
|
@ -1243,34 +1251,40 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
return true;
|
||||
|
||||
case OSD_CURRENT_DRAW:
|
||||
buff[0] = SYM_AMP;
|
||||
osdFormatCentiNumber(buff + 1, getAmperage(), 0, 2, 0, 3);
|
||||
|
||||
osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3);
|
||||
buff[3] = SYM_AMP;
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
|
||||
case OSD_MAH_DRAWN:
|
||||
buff[0] = SYM_MAH;
|
||||
tfp_sprintf(buff + 1, "%-4d", (int)getMAhDrawn());
|
||||
tfp_sprintf(buff, "%4d", (int)getMAhDrawn());
|
||||
buff[4] = SYM_MAH;
|
||||
buff[5] = '\0';
|
||||
osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr);
|
||||
break;
|
||||
|
||||
case OSD_WH_DRAWN:
|
||||
buff[0] = SYM_WH;
|
||||
osdFormatCentiNumber(buff + 1, getMWhDrawn() / 10, 0, 2, 0, 3);
|
||||
osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3);
|
||||
osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr);
|
||||
buff[3] = SYM_WH;
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
|
||||
case OSD_BATTERY_REMAINING_CAPACITY:
|
||||
buff[0] = (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH);
|
||||
|
||||
if (currentBatteryProfile->capacity.value == 0)
|
||||
tfp_sprintf(buff + 1, "NA");
|
||||
tfp_sprintf(buff, " NA");
|
||||
else if (!batteryWasFullWhenPluggedIn())
|
||||
tfp_sprintf(buff + 1, "NF");
|
||||
tfp_sprintf(buff, " NF");
|
||||
else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH)
|
||||
tfp_sprintf(buff + 1, "%-4lu", getBatteryRemainingCapacity());
|
||||
tfp_sprintf(buff, "%4lu", getBatteryRemainingCapacity());
|
||||
else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH
|
||||
osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3);
|
||||
|
||||
buff[3] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH;
|
||||
buff[4] = '\0';
|
||||
|
||||
if ((getBatteryState() != BATTERY_NOT_PRESENT) && batteryUsesCapacityThresholds() && (getBatteryRemainingCapacity() <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical))
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
|
||||
|
@ -1343,7 +1357,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
buff[0] = ARMING_FLAG(ARMED) ? '-' : SYM_ARROW_UP;
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
}
|
||||
buff[1] = 0;
|
||||
buff[1] = '\0';
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1376,7 +1390,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
break;
|
||||
|
||||
case OSD_TRIP_DIST:
|
||||
buff[0] = SYM_TRIP_DIST;
|
||||
buff[0] = SYM_TOTAL;
|
||||
osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance());
|
||||
break;
|
||||
|
||||
|
@ -1392,8 +1406,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
} else {
|
||||
buff[1] = buff[2] = buff[3] = '-';
|
||||
}
|
||||
buff[4] = SYM_DEGREES;
|
||||
buff[5] = '\0';
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1494,8 +1507,8 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
int32_t alt = osdGetAltitudeMsl();
|
||||
osdFormatAltitudeSymbol(buff, alt);
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
case OSD_ONTIME:
|
||||
{
|
||||
osdFormatOnTime(buff);
|
||||
|
@ -1557,12 +1570,13 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
}
|
||||
buff[0] = SYM_TRIP_DIST;
|
||||
if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) {
|
||||
buff[1] = SYM_DIST_M;
|
||||
strcpy(buff + 2, "---");
|
||||
buff[4] = SYM_DIST_M;
|
||||
buff[5] = '\0';
|
||||
strcpy(buff + 1, "---");
|
||||
} else if (distanceMeters == -2) {
|
||||
// Wind is too strong to come back with cruise throttle
|
||||
buff[1] = SYM_DIST_M;
|
||||
buff[2] = buff[3] = buff[4] = SYM_WIND_HORIZONTAL;
|
||||
buff[1] = buff[2] = buff[3] = SYM_WIND_HORIZONTAL;
|
||||
buff[4] = SYM_DIST_M;
|
||||
buff[5] = '\0';
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
} else {
|
||||
|
@ -2056,8 +2070,9 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_POWER:
|
||||
{
|
||||
buff[0] = SYM_WATT;
|
||||
osdFormatCentiNumber(buff + 1, getPower(), 0, 2, 0, 3);
|
||||
osdFormatCentiNumber(buff, getPower(), 0, 2, 0, 3);
|
||||
buff[3] = SYM_WATT;
|
||||
buff[4] = '\0';
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -2594,7 +2609,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
|||
osdConfig->item_pos[0][OSD_CRUISE_HEADING_ERROR] = OSD_POS(12, 2);
|
||||
osdConfig->item_pos[0][OSD_CRUISE_HEADING_ADJUSTMENT] = OSD_POS(12, 2);
|
||||
osdConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2);
|
||||
osdConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(1, 3) | OSD_VISIBLE_FLAG;
|
||||
osdConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG;
|
||||
osdConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG;
|
||||
osdConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5);
|
||||
osdConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6);
|
||||
|
|
|
@ -136,17 +136,17 @@ uint8_t esc4wayInit(void)
|
|||
pwmDisableMotors();
|
||||
escCount = 0;
|
||||
memset(&escHardware, 0, sizeof(escHardware));
|
||||
pwmIOConfiguration_t *pwmIOConfiguration = pwmGetOutputConfiguration();
|
||||
for (volatile uint8_t i = 0; i < pwmIOConfiguration->ioCount; i++) {
|
||||
if ((pwmIOConfiguration->ioConfigurations[i].flags & PWM_PF_MOTOR) == PWM_PF_MOTOR) {
|
||||
if (motor[pwmIOConfiguration->ioConfigurations[i].index] > 0) {
|
||||
escHardware[escCount].io = IOGetByTag(pwmIOConfiguration->ioConfigurations[i].timerHardware->tag);
|
||||
setEscInput(escCount);
|
||||
setEscHi(escCount);
|
||||
escCount++;
|
||||
}
|
||||
|
||||
for (int idx = 0; idx < getMotorCount(); idx++) {
|
||||
ioTag_t tag = pwmGetMotorPinTag(idx);
|
||||
if (tag != IOTAG_NONE) {
|
||||
escHardware[escCount].io = IOGetByTag(tag);
|
||||
setEscInput(escCount);
|
||||
setEscHi(escCount);
|
||||
escCount++;
|
||||
}
|
||||
}
|
||||
|
||||
return escCount;
|
||||
}
|
||||
|
||||
|
|
|
@ -23,13 +23,14 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||
#if defined(USE_RX_PPM)
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/rx_pwm.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
|
@ -40,14 +41,7 @@
|
|||
|
||||
#define RC_PWM_50HZ_UPDATE (20 * 1000) // 50Hz update rate period
|
||||
|
||||
#if MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT > MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT
|
||||
#define PWM_RX_CHANNEL_COUNT MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT
|
||||
#else
|
||||
#define PWM_RX_CHANNEL_COUNT MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT
|
||||
#endif
|
||||
|
||||
static uint16_t channelData[PWM_RX_CHANNEL_COUNT];
|
||||
static timeUs_t lastReceivedFrameUs;
|
||||
static uint16_t channelData[MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT];
|
||||
|
||||
static uint16_t readRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
|
||||
{
|
||||
|
@ -55,30 +49,6 @@ static uint16_t readRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan
|
|||
return channelData[channel];
|
||||
}
|
||||
|
||||
static uint8_t pwmFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
UNUSED(rxRuntimeConfig);
|
||||
|
||||
timeUs_t currentTimeUs = micros();
|
||||
|
||||
// PWM doesn't indicate individual updates, if low level code indicates that we have valid signal
|
||||
// we mimic the update at 50Hz rate
|
||||
|
||||
if (isPWMDataBeingReceived()) {
|
||||
if ((currentTimeUs - lastReceivedFrameUs) >= RC_PWM_50HZ_UPDATE) {
|
||||
lastReceivedFrameUs = currentTimeUs;
|
||||
|
||||
for (int channel = 0; channel < MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT; channel++) {
|
||||
channelData[channel] = pwmRead(channel);
|
||||
}
|
||||
|
||||
return RX_FRAME_COMPLETE;
|
||||
}
|
||||
}
|
||||
|
||||
return RX_FRAME_PENDING;
|
||||
}
|
||||
|
||||
static uint8_t ppmFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
UNUSED(rxRuntimeConfig);
|
||||
|
@ -96,21 +66,25 @@ static uint8_t ppmFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
return RX_FRAME_PENDING;
|
||||
}
|
||||
|
||||
void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool rxPpmInit(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
const timerHardware_t * timHw = timerGetByUsageFlag(TIM_USE_PPM);
|
||||
|
||||
if (timHw == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!ppmInConfig(timHw)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
rxRuntimeConfig->rxRefreshRate = RC_PWM_50HZ_UPDATE;
|
||||
rxRuntimeConfig->requireFiltering = true;
|
||||
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
|
||||
rxRuntimeConfig->rcReadRawFn = readRawRC;
|
||||
rxRuntimeConfig->rcFrameStatusFn = ppmFrameStatus;
|
||||
|
||||
// configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled
|
||||
if (rxConfig->receiverType == RX_TYPE_PWM) {
|
||||
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT;
|
||||
rxRuntimeConfig->rcReadRawFn = readRawRC;
|
||||
rxRuntimeConfig->rcFrameStatusFn = pwmFrameStatus;
|
||||
} else if (rxConfig->receiverType == RX_TYPE_PPM) {
|
||||
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
|
||||
rxRuntimeConfig->rcReadRawFn = readRawRC;
|
||||
rxRuntimeConfig->rcFrameStatusFn = ppmFrameStatus;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -17,4 +17,4 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
bool rxPpmInit(rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
|
|
@ -275,10 +275,13 @@ void rxInit(void)
|
|||
}
|
||||
|
||||
switch (rxConfig()->receiverType) {
|
||||
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||
case RX_TYPE_PWM:
|
||||
#if defined(USE_RX_PPM)
|
||||
case RX_TYPE_PPM:
|
||||
rxPwmInit(rxConfig(), &rxRuntimeConfig);
|
||||
if (!rxPpmInit(&rxRuntimeConfig)) {
|
||||
rxConfigMutable()->receiverType = RX_TYPE_NONE;
|
||||
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
|
||||
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
@ -314,9 +317,12 @@ void rxInit(void)
|
|||
break;
|
||||
#endif
|
||||
|
||||
case RX_TYPE_NONE:
|
||||
default:
|
||||
// Already configured for NONE
|
||||
case RX_TYPE_NONE:
|
||||
case RX_TYPE_PWM:
|
||||
rxConfigMutable()->receiverType = RX_TYPE_NONE;
|
||||
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
|
||||
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
|
@ -81,18 +81,11 @@ typedef enum {
|
|||
} rxSerialReceiverType_e;
|
||||
|
||||
#define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 16
|
||||
#define MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT 8
|
||||
#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18
|
||||
|
||||
#define NON_AUX_CHANNEL_COUNT 4
|
||||
#define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT)
|
||||
|
||||
#if MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT > MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT
|
||||
#define MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT
|
||||
#else
|
||||
#define MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT
|
||||
#endif
|
||||
|
||||
extern const char rcChannelLetters[];
|
||||
|
||||
#define MAX_MAPPABLE_RX_INPUTS 4
|
||||
|
|
|
@ -50,7 +50,6 @@
|
|||
#include "drivers/accgyro/accgyro_bmi160.h"
|
||||
#include "drivers/accgyro/accgyro_icm20689.h"
|
||||
#include "drivers/accgyro/accgyro_fake.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
@ -307,8 +306,6 @@ static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
|
|||
break;
|
||||
}
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_ACC_DETECTION, BOOT_EVENT_FLAGS_NONE, accHardware, 0, 0, 0);
|
||||
|
||||
if (accHardware == ACC_NONE) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -36,7 +36,6 @@
|
|||
#include "drivers/barometer/barometer_lps25h.h"
|
||||
#include "drivers/barometer/barometer_fake.h"
|
||||
#include "drivers/barometer/barometer_ms56xx.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -163,8 +162,6 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
|||
break;
|
||||
}
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_BARO_DETECTION, BOOT_EVENT_FLAGS_NONE, baroHardware, 0, 0, 0);
|
||||
|
||||
if (baroHardware == BARO_NONE) {
|
||||
sensorsClear(SENSOR_BARO);
|
||||
return false;
|
||||
|
|
|
@ -42,7 +42,6 @@
|
|||
#include "drivers/compass/compass_lis3mdl.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
@ -267,8 +266,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
|
|||
break;
|
||||
}
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_MAG_DETECTION, BOOT_EVENT_FLAGS_NONE, magHardware, 0, 0, 0);
|
||||
|
||||
if (magHardware == MAG_NONE) {
|
||||
sensorsClear(SENSOR_MAG);
|
||||
return false;
|
||||
|
@ -296,7 +293,6 @@ bool compassInit(void)
|
|||
LED1_OFF;
|
||||
|
||||
if (!ret) {
|
||||
addBootlogEvent2(BOOT_EVENT_MAG_INIT_FAILED, BOOT_EVENT_FLAGS_ERROR);
|
||||
sensorsClear(SENSOR_MAG);
|
||||
}
|
||||
|
||||
|
|
|
@ -53,7 +53,6 @@
|
|||
#include "drivers/accgyro/accgyro_icm20689.h"
|
||||
#include "drivers/accgyro/accgyro_fake.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -245,8 +244,6 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard
|
|||
gyroHardware = GYRO_NONE;
|
||||
}
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_GYRO_DETECTION, BOOT_EVENT_FLAGS_NONE, gyroHardware, 0, 0, 0);
|
||||
|
||||
if (gyroHardware != GYRO_NONE) {
|
||||
detectedSensors[SENSOR_INDEX_GYRO] = gyroHardware;
|
||||
sensorsSet(SENSOR_GYRO);
|
||||
|
|
|
@ -24,8 +24,6 @@
|
|||
|
||||
#include "config/config_eeprom.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
|
|
|
@ -42,7 +42,6 @@
|
|||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "drivers/opflow/opflow.h"
|
||||
|
@ -119,8 +118,6 @@ static bool opflowDetect(opflowDev_t * dev, uint8_t opflowHardwareToUse)
|
|||
break;
|
||||
}
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_OPFLOW_DETECTION, BOOT_EVENT_FLAGS_NONE, opflowHardware, 0, 0, 0);
|
||||
|
||||
if (opflowHardware == OPFLOW_NONE) {
|
||||
sensorsClear(SENSOR_OPFLOW);
|
||||
return false;
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/pitotmeter.h"
|
||||
#include "drivers/pitotmeter_ms4525.h"
|
||||
#include "drivers/pitotmeter_adc.h"
|
||||
|
@ -130,8 +129,6 @@ bool pitotDetect(pitotDev_t *dev, uint8_t pitotHardwareToUse)
|
|||
break;
|
||||
}
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_PITOT_DETECTION, BOOT_EVENT_FLAGS_NONE, pitotHardware, 0, 0, 0);
|
||||
|
||||
if (pitotHardware == PITOT_NONE) {
|
||||
sensorsClear(SENSOR_PITOT);
|
||||
return false;
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/rangefinder/rangefinder.h"
|
||||
#include "drivers/rangefinder/rangefinder_hcsr04.h"
|
||||
|
@ -166,8 +165,6 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar
|
|||
break;
|
||||
}
|
||||
|
||||
addBootlogEvent6(BOOT_EVENT_RANGEFINDER_DETECTION, BOOT_EVENT_FLAGS_NONE, rangefinderHardware, 0, 0, 0);
|
||||
|
||||
if (rangefinderHardware == RANGEFINDER_NONE) {
|
||||
sensorsClear(SENSOR_RANGEFINDER);
|
||||
return false;
|
||||
|
|
|
@ -28,7 +28,6 @@
|
|||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/1-wire.h"
|
||||
#include "drivers/logging.h"
|
||||
#include "drivers/temperature/temperature.h"
|
||||
#include "drivers/temperature/lm75.h"
|
||||
#include "drivers/temperature/ds18b20.h"
|
||||
|
@ -100,7 +99,6 @@ static void newSensorCheckAndEnter(uint8_t type, uint64_t addr)
|
|||
void temperatureInit(void)
|
||||
{
|
||||
memset(sensorStatus, 0, sizeof(sensorStatus) * sizeof(*sensorStatus));
|
||||
addBootlogEvent2(BOOT_EVENT_TEMP_SENSOR_DETECTION, BOOT_EVENT_FLAGS_NONE);
|
||||
|
||||
sensorsSet(SENSOR_TEMP);
|
||||
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
|
|
|
@ -24,6 +24,7 @@
|
|||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/serial.h"
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/serial.h"
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
#include "platform.h"
|
||||
#include "config/feature.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
#define BEEPER PB4
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_SERIALSHOT
|
||||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
|
|
|
@ -1,42 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0),
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_PWM | TIM_USE_LED, 0),
|
||||
DEF_TIM(TIM17, CH1, PB9, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
|
||||
DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
|
||||
DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
|
||||
DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0),
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0),
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
|
@ -1,160 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "SDF3" // STM Discovery F3
|
||||
|
||||
#define LED0 PE8 // Blue LEDs - PE8/PE12
|
||||
#define LED0_INVERTED
|
||||
#define LED1 PE10 // Orange LEDs - PE10/PE14
|
||||
#define LED1_INVERTED
|
||||
|
||||
#define BEEPER PE9 // Red LEDs - PE9/PE13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_FAKE_GYRO
|
||||
#define USE_GYRO_L3GD20
|
||||
#define L3GD20_SPI_BUS BUS_SPI1
|
||||
#define L3GD20_CS_PIN PE3
|
||||
#define GYRO_L3GD20_ALIGN CW270_DEG
|
||||
#define USE_GYRO_L3G4200D
|
||||
#define USE_GYRO_MPU3050
|
||||
#define USE_GYRO_MPU6050
|
||||
#define MPU6050_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_GYRO_MPU6000
|
||||
#define MPU6000_CS_PIN SPI2_NSS_PIN
|
||||
#define MPU6000_SPI_BUS BUS_SPI2
|
||||
|
||||
#define USE_GYRO_MPU6500
|
||||
#define MPU6500_CS_PIN SPI2_NSS_PIN
|
||||
#define MPU6500_SPI_BUS BUS_SPI2
|
||||
#define GYRO_MPU6500_ALIGN CW270_DEG_FLIP
|
||||
|
||||
#define USE_GYRO_MPU9250
|
||||
#define MPU9250_CS_PIN SPI2_NSS_PIN
|
||||
#define MPU9250_SPI_BUS BUS_SPI2
|
||||
#define GYRO_MPU9250_ALIGN CW270_DEG_FLIP
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_FAKE_ACC
|
||||
#define USE_ACC_ADXL345
|
||||
#define USE_ACC_BMA280
|
||||
#define USE_ACC_MMA8452
|
||||
#define USE_ACC_MPU6050
|
||||
#define USE_ACC_LSM303DLHC
|
||||
#define LSM303DLHC_I2C_BUS BUS_I2C1
|
||||
#define USE_ACC_MPU6000
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_MPU9250
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG_FLIP
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_FAKE_BARO
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_FAKE_MAG
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_MPU9250
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
|
||||
#define USE_PITOT_MS4525
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_UART4
|
||||
#define USE_UART5
|
||||
#define SERIAL_PORT_COUNT 6
|
||||
|
||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define USE_RX_NRF24
|
||||
#define NRF24_SPI_INSTANCE SPI2
|
||||
#define USE_RX_CX10
|
||||
#define USE_RX_H8_3D
|
||||
#define USE_RX_INAV
|
||||
#define USE_RX_SYMA
|
||||
#define USE_RX_V202
|
||||
#define RX_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_NSS_PIN PA0
|
||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_CE_PIN PA1
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define ADC_CHANNEL_3_PIN PC2
|
||||
#define ADC_CHANNEL_4_PIN PC3
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PB8 // TIM16_CH1
|
||||
|
||||
#define USE_SPEKTRUM_BIND
|
||||
#define BIND_PIN PA3 // USART2, PA3
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
#define USE_RANGEFINDER_HCSR04
|
||||
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0
|
||||
#define RANGEFINDER_HCSR04_ECHO_PIN PB1
|
||||
#define USE_RANGEFINDER_SRF10
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// Number of available PWM outputs
|
||||
#define MAX_PWM_OUTPUT_PORTS 12
|
||||
|
||||
// IO - 303 in 100pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
#define TARGET_IO_PORTF 0x00ff
|
|
@ -1,33 +0,0 @@
|
|||
F3_TARGETS += $(TARGET)
|
||||
FEATURES = VCP SDCARD
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_adxl345.c \
|
||||
drivers/accgyro/accgyro_bma280.c \
|
||||
drivers/accgyro/accgyro_fake.c \
|
||||
drivers/accgyro/accgyro_l3gd20.c \
|
||||
drivers/accgyro/accgyro_l3g4200d.c \
|
||||
drivers/accgyro/accgyro_lsm303dlhc.c \
|
||||
drivers/accgyro/accgyro_mma845x.c \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu3050.c \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/accgyro/accgyro_mpu6050.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_mpu9250.c \
|
||||
drivers/barometer/barometer_bmp085.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_fake.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_ak8963.c \
|
||||
drivers/compass/compass_ak8975.c \
|
||||
drivers/compass/compass_mpu9250.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_fake.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
|
|
@ -27,7 +27,6 @@
|
|||
#define I2C2_OVERCLOCK false
|
||||
#define USE_I2C_PULLUP // Enable built-in pullups on all boards in case external ones are too week
|
||||
|
||||
#define USE_RX_PWM
|
||||
#define USE_RX_PPM
|
||||
#define USE_SERIAL_RX
|
||||
#define USE_SERIALRX_SPEKTRUM // Cheap and fairly common protocol
|
||||
|
@ -99,12 +98,13 @@
|
|||
|
||||
#define USE_PWM_DRIVER_PCA9685
|
||||
|
||||
#define USE_BOOTLOG
|
||||
#define BOOTLOG_DESCRIPTIONS
|
||||
|
||||
#define NAV_NON_VOLATILE_WAYPOINT_CLI
|
||||
|
||||
#define NAV_AUTO_MAG_DECLINATION_PRECISE
|
||||
|
||||
#define USE_D_BOOST
|
||||
|
||||
|
||||
#else // FLASH_SIZE < 256
|
||||
#define LOG_LEVEL_MAXIMUM LOG_LEVEL_ERROR
|
||||
#endif
|
||||
|
@ -141,7 +141,6 @@
|
|||
#define USE_PWM_SERVO_DRIVER
|
||||
#define USE_SERIAL_PASSTHROUGH
|
||||
#define NAV_MAX_WAYPOINTS 60
|
||||
#define MAX_BOOTLOG_ENTRIES 64
|
||||
#define USE_RCDEVICE
|
||||
#define USE_PITOT
|
||||
#define USE_PITOT_ADC
|
||||
|
|
|
@ -140,8 +140,6 @@ timeMs_t millis(void) {return milliTime++;}
|
|||
uint32_t micros(void) {return 0;}
|
||||
void beeper(beeperMode_e) {}
|
||||
uint8_t detectedSensors[] = { GYRO_NONE, ACC_NONE };
|
||||
void addBootlogEvent6(bootLogEventCode_e eventCode, uint16_t eventFlags, uint16_t param1, uint16_t param2, uint16_t param3, uint16_t param4)
|
||||
{UNUSED(eventCode);UNUSED(eventFlags);UNUSED(param1);UNUSED(param2);UNUSED(param3);UNUSED(param4);}
|
||||
timeDelta_t getLooptime(void) {return gyro.targetLooptime;}
|
||||
void sensorsSet(uint32_t) {}
|
||||
void schedulerResetTaskStatistics(cfTaskId_e) {}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue