diff --git a/src/board.h b/src/board.h index a434f7bee..69a9a7e45 100755 --- a/src/board.h +++ b/src/board.h @@ -74,6 +74,7 @@ typedef enum { FEATURE_POWERMETER = 1 << 12, FEATURE_VARIO = 1 << 13, FEATURE_3D = 1 << 14, + FEATURE_SOFTSERIAL = 1 << 15, } AvailableFeatures; typedef enum { diff --git a/src/cli.c b/src/cli.c index bcc7b0102..55c60b26c 100644 --- a/src/cli.c +++ b/src/cli.c @@ -44,7 +44,7 @@ static const char * const mixerNames[] = { static const char * const featureNames[] = { "PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP", "SERVO_TILT", "GYRO_SMOOTHING", "LED_RING", "GPS", - "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", + "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", "SOFTSERIAL", NULL }; @@ -115,6 +115,8 @@ const clivalue_t valueTable[] = { { "servo_pwm_rate", VAR_UINT16, &mcfg.servo_pwm_rate, 50, 498 }, { "retarded_arm", VAR_UINT8, &mcfg.retarded_arm, 0, 1 }, { "serial_baudrate", VAR_UINT32, &mcfg.serial_baudrate, 1200, 115200 }, + { "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 9600, 19200 }, + { "softserial_inverted", VAR_UINT8, &mcfg.softserial_inverted, 0, 1 }, { "gps_baudrate", VAR_UINT32, &mcfg.gps_baudrate, 1200, 115200 }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 2 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, diff --git a/src/config.c b/src/config.c index 2cbbc2272..3295555e5 100755 --- a/src/config.c +++ b/src/config.c @@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles config_t cfg; // profile config struct const char rcChannelLetters[] = "AERT1234"; -static const uint8_t EEPROM_CONF_VERSION = 51; +static const uint8_t EEPROM_CONF_VERSION = 52; static uint32_t enabledSensors = 0; static void resetConf(void); @@ -209,6 +209,8 @@ static void resetConf(void) mcfg.gps_baudrate = 115200; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; + mcfg.softserial_baudrate = 19200; + mcfg.softserial_inverted = 0; mcfg.looptime = 3500; mcfg.rssi_aux_channel = 0; diff --git a/src/drv_pwm.c b/src/drv_pwm.c index 77dfc20aa..8c1247bc6 100755 --- a/src/drv_pwm.c +++ b/src/drv_pwm.c @@ -323,11 +323,9 @@ bool pwmInit(drv_pwm_config_t *init) if (init->useUART && (port == PWM3 || port == PWM4)) continue; -#ifdef SOFTSERIAL_19200_LOOPBACK // skip softSerial ports - if ((port == PWM5 || port == PWM6 || port == PWM7 || port == PWM8)) + if (init->useSoftSerial && (port == PWM5 || port == PWM6 || port == PWM7 || port == PWM8)) continue; -#endif // skip ADC for powerMeter if configured if (init->adcChannel && (init->adcChannel == port)) diff --git a/src/drv_pwm.h b/src/drv_pwm.h index a56e281a2..728ac8eec 100755 --- a/src/drv_pwm.h +++ b/src/drv_pwm.h @@ -8,6 +8,7 @@ typedef struct drv_pwm_config_t { bool enableInput; bool usePPM; bool useUART; + bool useSoftSerial; bool useServos; bool extraServos; // configure additional 4 channels in PPM mode as servos, not motors bool airplane; // fixed wing hardware config, lots of servos etc diff --git a/src/drv_softserial.c b/src/drv_softserial.c index a2bd1aca7..b96b56d0e 100644 --- a/src/drv_softserial.c +++ b/src/drv_softserial.c @@ -17,12 +17,16 @@ void onSerialTimer(uint8_t portIndex, uint16_t capture); uint8_t readRxSignal(softSerial_t *softSerial) { - return !(digitalIn(softSerial->rxTimerHardware->gpio, softSerial->rxTimerHardware->pin) == 0); + uint8_t invertedSignal = (digitalIn(softSerial->rxTimerHardware->gpio, softSerial->rxTimerHardware->pin) == 0); + if (softSerial->isInverted) { + return invertedSignal; + } + return !invertedSignal; } void setTxSignal(softSerial_t *softSerial, uint8_t state) { - if (state) { + if ((state == 1 && softSerial->isInverted == false) || (state == 0 && softSerial->isInverted == true)) { digitalHi(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin); } else { digitalLo(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin); @@ -82,7 +86,7 @@ void serialOutputPortConfig(const timerHardware_t *timerHardwarePtr) softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_Out_PP); } -void setupSoftSerial1(uint32_t baud) +void setupSoftSerial1(uint32_t baud, uint8_t inverted) { int portIndex = 0; softSerial_t *softSerial = &(softSerialPorts[portIndex]); @@ -90,6 +94,7 @@ void setupSoftSerial1(uint32_t baud) softSerial->port.vTable = softSerialVTable; softSerial->port.mode = MODE_RXTX; softSerial->port.baudRate = baud; + softSerial->isInverted = inverted; softSerial->rxTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_RX_HARDWARE]); softSerial->txTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_TX_HARDWARE]); diff --git a/src/drv_softserial.h b/src/drv_softserial.h index ad2b60dc4..c16135c4f 100644 --- a/src/drv_softserial.h +++ b/src/drv_softserial.h @@ -29,6 +29,7 @@ typedef struct softSerial_s { uint16_t internalRxBuffer; // excluding start/stop bits uint16_t internalTxBuffer; // includes start and stop bits + uint8_t isInverted; } softSerial_t; extern timerHardware_t* serialTimerHardware; @@ -36,7 +37,7 @@ extern softSerial_t softSerialPorts[]; extern const struct serialPortVTable softSerialVTable[]; -void setupSoftSerial1(uint32_t baud); +void setupSoftSerial1(uint32_t baud, uint8_t inverted); // serialPort API void softSerialWriteByte(serialPort_t *instance, uint8_t ch); diff --git a/src/main.c b/src/main.c index 90c7bfdfd..7a0e506f1 100755 --- a/src/main.c +++ b/src/main.c @@ -30,6 +30,7 @@ int main(void) uint8_t i; drv_pwm_config_t pwm_params; drv_adc_config_t adc_params; + serialPort_t* loopbackPort = NULL; systemInit(); #ifdef USE_LAME_PRINTF @@ -59,6 +60,7 @@ int main(void) else pwm_params.airplane = false; pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SERIALRX); // spektrum/sbus support uses UART too + pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL); pwm_params.usePPM = feature(FEATURE_PPM); pwm_params.enableInput = !feature(FEATURE_SERIALRX); // disable inputs if using spektrum pwm_params.useServos = core.useServo; @@ -130,11 +132,14 @@ int main(void) batteryInit(); serialInit(mcfg.serial_baudrate); -#ifdef SOFTSERIAL_19200_LOOPBACK - setupSoftSerial1(19200); - serialPort_t* loopbackPort = (serialPort_t*)&(softSerialPorts[0]); - serialPrint(loopbackPort, "LOOPBACK 19200 ENABLED\r\n"); + + if (feature(FEATURE_SOFTSERIAL)) { + setupSoftSerial1(mcfg.softserial_baudrate, mcfg.softserial_inverted); +#ifdef SOFTSERIAL_LOOPBACK + loopbackPort = (serialPort_t*)&(softSerialPorts[0]); + serialPrint(loopbackPort, "LOOPBACK ENABLED\r\n"); #endif + } previousTime = micros(); if (mcfg.mixerConfiguration == MULTITYPE_GIMBAL) @@ -146,13 +151,15 @@ int main(void) // loopy while (1) { loop(); -#ifdef SOFTSERIAL_19200_LOOPBACK - while (serialTotalBytesWaiting(loopbackPort)) { - - uint8_t b = serialRead(loopbackPort); - serialWrite(loopbackPort, b); - //serialWrite(core.mainport, b); - }; +#ifdef SOFTSERIAL_LOOPBACK + if (loopbackPort) { + while (serialTotalBytesWaiting(loopbackPort)) { + + uint8_t b = serialRead(loopbackPort); + serialWrite(loopbackPort, b); + //serialWrite(core.mainport, b); + }; + } #endif } } diff --git a/src/mw.h b/src/mw.h index df724a994..f8200e919 100755 --- a/src/mw.h +++ b/src/mw.h @@ -290,6 +290,9 @@ typedef struct master_t { uint32_t gps_baudrate; // GPS baudrate uint32_t serial_baudrate; + + uint32_t softserial_baudrate; + uint8_t softserial_inverted; // use inverted softserial input and output signals config_t profile[3]; // 3 separate profiles uint8_t current_profile; // currently loaded profile