This commit is contained in:
borisbstyle 2016-08-04 01:31:46 +02:00
commit 166d81679b
22 changed files with 330 additions and 31 deletions

View File

@ -72,6 +72,7 @@
#include "flight/altitudehold.h" #include "flight/altitudehold.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/pid.h"
#include "flight/navigation.h" #include "flight/navigation.h"
#include "config/runtime_config.h" #include "config/runtime_config.h"

View File

@ -53,6 +53,7 @@
#include "flight/altitudehold.h" #include "flight/altitudehold.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/pid.h"
#include "flight/navigation.h" #include "flight/navigation.h"
#include "config/runtime_config.h" #include "config/runtime_config.h"

View File

@ -23,6 +23,7 @@
#include "debug.h" #include "debug.h"
#include "build_config.h" #include "build_config.h"
#include "debug.h"
#include "blackbox/blackbox_io.h" #include "blackbox/blackbox_io.h"

View File

@ -21,8 +21,8 @@
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT)) #define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT #define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT
#include "drivers/io.h" #include "io.h"
#include "drivers/rcc.h" #include "rcc.h"
#ifndef I2C_DEVICE #ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID #define I2C_DEVICE I2CINVALID

View File

@ -18,7 +18,7 @@
#pragma once #pragma once
#include "drivers/io.h" #include "io.h"
// old EXTI interface, to be replaced // old EXTI interface, to be replaced
typedef struct extiConfig_s { typedef struct extiConfig_s {

View File

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "drivers/io.h" #include "io.h"
#ifdef BEEPER #ifdef BEEPER
#define BEEP_TOGGLE systemBeepToggle() #define BEEP_TOGGLE systemBeepToggle()

View File

@ -15,19 +15,21 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "io/escservo.h" #pragma once
#include "io/rc_controls.h"
#include "flight/pid.h"
#include "sensors/barometer.h"
extern int32_t AltHold; extern int32_t AltHold;
extern int32_t vario; extern int32_t vario;
void calculateEstimatedAltitude(uint32_t currentTime); void calculateEstimatedAltitude(uint32_t currentTime);
void configureAltitudeHold(pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig, rcControlsConfig_t *initialRcControlsConfig, escAndServoConfig_t *initialEscAndServoConfig); struct pidProfile_s;
void applyAltHold(airplaneConfig_t *airplaneConfig); struct barometerConfig_s;
struct rcControlsConfig_s;
struct escAndServoConfig_s;
void configureAltitudeHold(struct pidProfile_s *initialPidProfile, struct barometerConfig_s *intialBarometerConfig, struct rcControlsConfig_s *initialRcControlsConfig, struct escAndServoConfig_s *initialEscAndServoConfig);
struct airplaneConfig_t;
void applyAltHold(struct airplaneConfig_s *airplaneConfig);
void updateAltHoldState(void); void updateAltHoldState(void);
void updateSonarAltHoldState(void); void updateSonarAltHoldState(void);

View File

@ -69,9 +69,10 @@ typedef struct accProcessor_s {
accProcessorState_e state; accProcessorState_e state;
} accProcessor_t; } accProcessor_t;
struct pidProfile_s;
void imuConfigure( void imuConfigure(
imuRuntimeConfig_t *initialImuRuntimeConfig, imuRuntimeConfig_t *initialImuRuntimeConfig,
pidProfile_t *initialPidProfile, struct pidProfile_s *initialPidProfile,
accDeadband_t *initialAccDeadband, accDeadband_t *initialAccDeadband,
uint16_t throttle_correction_angle uint16_t throttle_correction_angle
); );

View File

@ -14,7 +14,6 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "rx/rx.h"
#pragma once #pragma once

View File

@ -63,6 +63,8 @@
#include "io/display.h" #include "io/display.h"
#include "rx/rx.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
extern profile_t *currentProfile; extern profile_t *currentProfile;

View File

@ -17,8 +17,6 @@
#pragma once #pragma once
#include "rx/rx.h"
typedef enum { typedef enum {
BOXARM = 0, BOXARM = 0,
BOXANGLE, BOXANGLE,
@ -167,8 +165,9 @@ typedef struct rcControlsConfig_s {
bool areUsingSticksToArm(void); bool areUsingSticksToArm(void);
bool areSticksInApModePosition(uint16_t ap_mode); bool areSticksInApModePosition(uint16_t ap_mode);
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle); struct rxConfig_s;
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch); throttleStatus_e calculateThrottleStatus(struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
void processRcStickPositions(struct rxConfig_s *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch);
bool isRangeActive(uint8_t auxChannelIndex, channelRange_t *range); bool isRangeActive(uint8_t auxChannelIndex, channelRange_t *range);
void updateActivatedModes(modeActivationCondition_t *modeActivationConditions); void updateActivatedModes(modeActivationCondition_t *modeActivationConditions);
@ -257,7 +256,7 @@ bool isAirmodeActive(void);
bool isSuperExpoActive(void); bool isSuperExpoActive(void);
void resetAdjustmentStates(void); void resetAdjustmentStates(void);
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges); void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig); void processRcAdjustments(controlRateConfig_t *controlRateConfig, struct rxConfig_s *rxConfig);
bool isUsingSticksForArming(void); bool isUsingSticksForArming(void);

View File

@ -18,12 +18,13 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include "io/rc_controls.h" #include "config/config.h"
#include "io/escservo.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h" #include "io/rc_curves.h"
#include "config/config.h" #include "rx/rx.h"
#define THROTTLE_LOOKUP_LENGTH 12 #define THROTTLE_LOOKUP_LENGTH 12
static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE

View File

@ -41,6 +41,8 @@
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/pwm_rx.h" #include "drivers/pwm_rx.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "rx/rx.h"
#include "rx/pwm.h" #include "rx/pwm.h"
#include "rx/sbus.h" #include "rx/sbus.h"
#include "rx/spektrum.h" #include "rx/spektrum.h"
@ -51,8 +53,6 @@
#include "rx/ibus.h" #include "rx/ibus.h"
#include "rx/jetiexbus.h" #include "rx/jetiexbus.h"
#include "rx/rx.h"
//#define DEBUG_RX_SIGNAL_LOSS //#define DEBUG_RX_SIGNAL_LOSS

View File

@ -17,7 +17,5 @@
#pragma once #pragma once
#include "rx/rx.h"
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback); bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
uint8_t xBusFrameStatus(void); uint8_t xBusFrameStatus(void);

View File

@ -35,6 +35,8 @@
#include "io/rc_controls.h" #include "io/rc_controls.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "rx/rx.h"
#define VBATT_PRESENT_THRESHOLD_MV 10 #define VBATT_PRESENT_THRESHOLD_MV 10
#define VBATT_LPF_FREQ 0.4f #define VBATT_LPF_FREQ 0.4f

View File

@ -0,0 +1,103 @@
/*
* 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"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
PWM4 | (MAP_TO_PWM_INPUT << 8),
PWM5 | (MAP_TO_PWM_INPUT << 8),
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PPM
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S2_IN
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S3_IN
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S4_IN
{ TIM9, IO_TAG(PE6), TIM_Channel_1, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S5_IN
{ TIM9, IO_TAG(PE7), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S6_IN
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S1_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S3_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S4_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S6_OUT
};

View File

@ -0,0 +1,180 @@
/*
* 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 "VRRA"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#define USBD_PRODUCT_STRING "VRRACE"
#define LED0 PD14
#define LED1 PD15
#define BEEPER PA0
#define BEEPER_INVERTED
#define INVERTER PD7
#define INVERTER_USART USART6
#define MPU6500_CS_PIN PE10
#define MPU6500_SPI_INSTANCE SPI2
#define ACC
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6500
#define GYRO_MPU6500_ALIGN CW270_DEG
// MPU6500 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
#define MPU_INT_EXTI PD10
#define USE_EXTI
/*
#define BARO
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12
*/
/*
#define SDCARD_DETECT_PIN PD2
#define SDCARD_DETECT_EXTI_LINE EXTI_Line2
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOD
#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PB3
*/
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
/*
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
*/
// Divide to under 25MHz for normal operation:
/*
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
*/
/*
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
*/
/*
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3
#define M25P16_SPI_INSTANCE SPI3
*/
#define USE_VCP
#define VBUS_SENSING_PIN PA9
//#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define USE_UART2
#define UART2_RX_PIN PD6
#define UART2_TX_PIN PD5
#define USE_UART3
#define UART3_RX_PIN PD9
#define UART3_TX_PIN PD8
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define USE_SOFTSERIAL1
#define SOFTSERIAL_1_TIMER TIM1
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2
#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART2, USART3, USART6, SOFTSERIAL1
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PE10
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
/*
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PB3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB8-SCL, PB8-SDA
#define USE_I2C_PULLUP
#define I2C1_SCL PB8
#define I2C1_SDA PB9
*/
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define VBAT_ADC_PIN PC0
#define RSSI_ADC_GPIO_PIN PB1
#define CURRENT_METER_ADC_PIN PA5
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_ONESHOT125 | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
/*
#define SPEKTRUM_BIND
// USART3 Rx, PB11
#define BIND_PIN PB11
*/
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#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 USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )

View File

@ -0,0 +1,7 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP
TARGET_SRC = \
drivers/accgyro_spi_mpu6000.c \
drivers/accgyro_spi_mpu6500.c \
drivers/accgyro_mpu6500.c

View File

@ -17,14 +17,13 @@
#pragma once #pragma once
#include "rx/rx.h"
typedef enum { typedef enum {
FRSKY_VFAS_PRECISION_LOW = 0, FRSKY_VFAS_PRECISION_LOW = 0,
FRSKY_VFAS_PRECISION_HIGH FRSKY_VFAS_PRECISION_HIGH
} frskyVFasPrecision_e; } frskyVFasPrecision_e;
void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle); struct rxConfig_s;
void handleFrSkyTelemetry(struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
void checkFrSkyTelemetryState(void); void checkFrSkyTelemetryState(void);
void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig); void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig);

View File

@ -488,7 +488,8 @@ typedef struct HOTT_AIRESC_MSG_s {
void handleHoTTTelemetry(void); void handleHoTTTelemetry(void);
void checkHoTTTelemetryState(void); void checkHoTTTelemetryState(void);
void initHoTTTelemetry(telemetryConfig_t *telemetryConfig); struct telemetryConfig_s;
void initHoTTTelemetry(struct telemetryConfig_s *telemetryConfig);
void configureHoTTTelemetryPort(void); void configureHoTTTelemetryPort(void);
void freeHoTTTelemetryPort(void); void freeHoTTTelemetryPort(void);

View File

@ -19,7 +19,8 @@
#pragma once #pragma once
void initLtmTelemetry(telemetryConfig_t *initialTelemetryConfig); struct telemetryConfig_s;
void initLtmTelemetry(struct telemetryConfig_s *initialTelemetryConfig);
void handleLtmTelemetry(void); void handleLtmTelemetry(void);
void checkLtmTelemetryState(void); void checkLtmTelemetryState(void);

View File

@ -7,7 +7,8 @@
#pragma once #pragma once
void initSmartPortTelemetry(telemetryConfig_t *); struct telemetryConfig_s;
void initSmartPortTelemetry(struct telemetryConfig_s *);
void handleSmartPortTelemetry(void); void handleSmartPortTelemetry(void);
void checkSmartPortTelemetryState(void); void checkSmartPortTelemetryState(void);