From 0b41697a8db694a53c1aed903c57e11cfce1966d Mon Sep 17 00:00:00 2001 From: jflyper Date: Fri, 9 Dec 2016 17:56:39 +0900 Subject: [PATCH] Disabled dprintf & set OPTIMIZE to -O2 (for testing) Makefile should eventually get coherent with system wide settings once #1747 is done. --- Makefile | 3 +- src/main/io/serial.h.orig | 158 ----------------------------------- src/main/io/vtx_smartaudio.c | 2 +- 3 files changed, 3 insertions(+), 160 deletions(-) delete mode 100644 src/main/io/serial.h.orig diff --git a/Makefile b/Makefile index f2edc40d58..244922fecb 100644 --- a/Makefile +++ b/Makefile @@ -760,7 +760,8 @@ else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) OPTIMIZE = -Os else -OPTIMIZE = -Ofast +#OPTIMIZE = -Ofast +OPTIMIZE = -O2 endif LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) endif diff --git a/src/main/io/serial.h.orig b/src/main/io/serial.h.orig deleted file mode 100644 index cc23aa7c99..0000000000 --- a/src/main/io/serial.h.orig +++ /dev/null @@ -1,158 +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 . - */ - -#pragma once - -#include "drivers/serial.h" - -typedef enum { - PORTSHARING_UNUSED = 0, - PORTSHARING_NOT_SHARED, - PORTSHARING_SHARED -} portSharing_e; - -typedef enum { - FUNCTION_NONE = 0, - FUNCTION_MSP = (1 << 0), // 1 - FUNCTION_GPS = (1 << 1), // 2 - FUNCTION_TELEMETRY_FRSKY = (1 << 2), // 4 - FUNCTION_TELEMETRY_HOTT = (1 << 3), // 8 - FUNCTION_TELEMETRY_LTM = (1 << 4), // 16 - FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), // 32 - FUNCTION_RX_SERIAL = (1 << 6), // 64 - FUNCTION_BLACKBOX = (1 << 7), // 128 - - FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512 -<<<<<<< HEAD - FUNCTION_TELEMETRY_ESC = (1 << 10), // 1024 - FUNCTION_VTX_CONTROL = (1 << 11),// 2048 -======= - FUNCTION_TELEMETRY_ESC = (1 << 10) // 1024 ->>>>>>> betaflight/master -} serialPortFunction_e; - -typedef enum { - BAUD_AUTO = 0, - BAUD_9600, - BAUD_19200, - BAUD_38400, - BAUD_57600, - BAUD_115200, - BAUD_230400, - BAUD_250000, - BAUD_400000, - BAUD_460800, - BAUD_500000, - BAUD_921600, - BAUD_1000000, - BAUD_1500000, - BAUD_2000000, - BAUD_2470000 -} baudRate_e; - -extern const uint32_t baudRates[]; - -// serial port identifiers are now fixed, these values are used by MSP commands. -typedef enum { - SERIAL_PORT_NONE = -1, - SERIAL_PORT_USART1 = 0, - SERIAL_PORT_USART2, - SERIAL_PORT_USART3, - SERIAL_PORT_USART4, - SERIAL_PORT_USART5, - SERIAL_PORT_USART6, - SERIAL_PORT_USART7, - SERIAL_PORT_USART8, - SERIAL_PORT_USB_VCP = 20, - SERIAL_PORT_SOFTSERIAL1 = 30, - SERIAL_PORT_SOFTSERIAL2 -} serialPortIdentifier_e; - -extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT]; - -// -// runtime -// -typedef struct serialPortUsage_s { - serialPortIdentifier_e identifier; - serialPort_t *serialPort; - serialPortFunction_e function; -} serialPortUsage_t; - -serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction); -serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction); - -// -// configuration -// -typedef struct serialPortConfig_s { - serialPortIdentifier_e identifier; - uint16_t functionMask; - uint8_t msp_baudrateIndex; - uint8_t gps_baudrateIndex; - uint8_t blackbox_baudrateIndex; - uint8_t telemetry_baudrateIndex; // not used for all telemetry systems, e.g. HoTT only works at 19200. -} serialPortConfig_t; - -typedef struct serialConfig_s { - uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else. - serialPortConfig_t portConfigs[SERIAL_PORT_COUNT]; -} serialConfig_t; - -typedef void serialConsumer(uint8_t); - -// -// configuration -// -void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled, serialPortIdentifier_e serialPortToDisable); -void serialRemovePort(serialPortIdentifier_e identifier); -uint8_t serialGetAvailablePortCount(void); -bool serialIsPortAvailable(serialPortIdentifier_e identifier); -bool isSerialConfigValid(serialConfig_t *serialConfig); -serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier); -bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier); -serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function); -serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function); - -portSharing_e determinePortSharing(serialPortConfig_t *portConfig, serialPortFunction_e function); -bool isSerialPortShared(serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction); - -serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier); -int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier); -// -// runtime -// -serialPort_t *openSerialPort( - serialPortIdentifier_e identifier, - serialPortFunction_e function, - serialReceiveCallbackPtr rxCallback, - uint32_t baudrate, - portMode_t mode, - portOptions_t options -); -void closeSerialPort(serialPort_t *serialPort); - -void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort); - -baudRate_e lookupBaudRateIndex(uint32_t baudRate); - - -// -// msp/cli/bootloader -// -void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar); -void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC); diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 7b23301b08..5b335a2246 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -29,7 +29,7 @@ #include "build/build_config.h" -#define SMARTAUDIO_DPRINTF +//#define SMARTAUDIO_DPRINTF //#define SMARTAUDIO_DEBUG_MONITOR #ifdef SMARTAUDIO_DPRINTF