1
0
Fork 0
mirror of https://github.com/opentx/opentx.git synced 2025-07-25 17:25:13 +03:00

Telemetry/AVR/Unify serial driver

This commit is contained in:
PT_Dreamer 2016-12-19 17:54:20 +00:00 committed by Bertrand Songis
parent 2f9d9c1a99
commit f83aef4606
11 changed files with 181 additions and 392 deletions

View file

@ -27,7 +27,6 @@
#include "opentx.h" #include "opentx.h"
#include "telemetry/mavlink.h" #include "telemetry/mavlink.h"
#include "targets/common/avr/serial_driver.h"
#define APSIZE (BSS | DBLSIZE) #define APSIZE (BSS | DBLSIZE)

View file

@ -130,7 +130,7 @@ bool sportWaitState(SportUpdateState state, int timeout)
for (int i=timeout/2; i>=0; i--) { for (int i=timeout/2; i>=0; i--) {
uint8_t byte ; uint8_t byte ;
while (telemetryGetByte(&byte)) { while (telemetryGetByte(&byte)) {
processFrskyTelemetryData(byte); processSerialData(byte);
} }
if (sportUpdateState == state) { if (sportUpdateState == state) {
return true; return true;

View file

@ -77,7 +77,11 @@ elseif(TELEMETRY STREQUAL JETI)
elseif(TELEMETRY STREQUAL MAVLINK) elseif(TELEMETRY STREQUAL MAVLINK)
add_definitions(-DTELEMETRY_MAVLINK) add_definitions(-DTELEMETRY_MAVLINK)
include_directories(${THIRDPARTY_DIR} gui/${GUI_DIR} targets/common/avr) include_directories(${THIRDPARTY_DIR} gui/${GUI_DIR} targets/common/avr)
set(SRC ${SRC} telemetry/mavlink.cpp targets/common/avr/serial_driver.cpp) set(FIRMWARE_SRC
${FIRMWARE_SRC}
targets/common/avr/telemetry_driver.cpp
)
set(SRC ${SRC} telemetry/mavlink.cpp)
set(GUI_SRC ${GUI_SRC} view_mavlink.cpp) set(GUI_SRC ${GUI_SRC} view_mavlink.cpp)
math(EXPR EEPROM_VARIANT ${EEPROM_VARIANT}+${MAVLINK_VARIANT}) math(EXPR EEPROM_VARIANT ${EEPROM_VARIANT}+${MAVLINK_VARIANT})
elseif(TELEMETRY STREQUAL TELEMETREZ) elseif(TELEMETRY STREQUAL TELEMETREZ)

View file

@ -220,4 +220,6 @@ uint8_t eepromIsTransferComplete();
#define TLM_USART 0 #define TLM_USART 0
#endif #endif
void telemetryPortInit(); void telemetryPortInit();
void telemetryPortInit(uint32_t baudrate);
void telemetryPortInitFromIndex(uint8_t index);
void telemetryTransmitBuffer(); void telemetryTransmitBuffer();

View file

@ -1,306 +0,0 @@
/*
* Copyright (C) OpenTX
*
* Based on code named
* th9x - http://code.google.com/p/th9x
* er9x - http://code.google.com/p/er9x
* gruvin9x - http://code.google.com/p/gruvin9x
*
* License GPLv2: http://www.gnu.org/licenses/gpl-2.0.html
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License version 2 as
* published by the Free Software Foundation.
*
* This program 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.
*/
#include "serial_driver.h"
#include "opentx.h"
/*
Receive serial (RS-232) characters, detecting and storing each Fr-Sky
0x7e-framed packet as it arrives. When a complete packet has been
received, process its data into storage variables. NOTE: This is an
interrupt routine and should not get too lengthy. I originally had
the buffer being checked in the perMain function (because per10ms
isn't quite often enough for data streaming at 9600baud) but alas
that scheme lost packets also. So each packet is parsed as it arrives,
directly at the ISR function (through a call to frskyProcessPacket).
If this proves a problem in the future, then I'll just have to implement
a second buffer to receive data while one buffer is being processed (slowly).
*/
#if !defined(SIMU)
ISR (USART0_RX_vect)
{
uint8_t iostat; //USART control and Status Register 0 A
// uint8_t rh; //USART control and Status Register 0 B
UCSR0B &= ~(1 << RXCIE0); // disable Interrupt
sei();
iostat = UCSR0A; //USART control and Status Register 0 A
uint8_t byte = UDR0;
/*
bit 7 6 5 4 3 2 1 0
RxC0 TxC0 UDRE0 FE0 DOR0 UPE0 U2X0 MPCM0
RxC0: Receive complete
TXC0: Transmit Complete
UDRE0: USART Data Register Empty
FE0: Frame Error
DOR0: Data OverRun
UPE0: USART Parity Error
U2X0: Double Tx Speed
MPCM0: MultiProcessor Comms Mode
*/
if (iostat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0))) {
byte = 0;
}
//rh = UCSR0B; //USART control and Status Register 0 B
#if defined(TELEMETRY_MAVLINK)
(RXHandler)(byte);
#endif
cli();
UCSR0B |= (1 << RXCIE0); // enable Interrupt
}
#endif
inline void SERIAL_EnableRXD(void) {
UCSR0B |= (1 << RXEN0); // enable RX
UCSR0B |= (1 << RXCIE0); // enable Interrupt
}
#if 0
void SERIAL_DisableRXD(void) {
UCSR0B &= ~(1 << RXEN0); // disable RX
UCSR0B &= ~(1 << RXCIE0); // disable Interrupt
}
#endif
/*
USART0 (transmit) Data Register Emtpy ISR
Usef to transmit FrSky data packets, which are buffered in frskyTXBuffer.
*/
uint8_t serialTxBuffer[MAX_TX_BUFFER]; // 32 characters
uint8_t serialTxBufferCount = 0;
uint8_t * ptrTxISR = 0;
serial_tx_state_t serialTxState = TX_STATE_EMPTY;
#ifndef SIMU
ISR(USART0_UDRE_vect)
{
if (serialTxBufferCount > 0) {
UDR0 = *ptrTxISR++;
serialTxBufferCount--;
}
else {
UCSR0B &= ~(1 << UDRIE0); // disable UDRE0 interrupt
serialTxState = TX_STATE_EMPTY;
}
}
#endif
void SERIAL_start_uart_send() {
ptrTxISR = serialTxBuffer;
serialTxBufferCount = 0;
}
void SERIAL_end_uart_send() {
ptrTxISR = serialTxBuffer;
//UCSR0B |= (1 << UDRIE0); // enable UDRE0 interrupt
serialTxState = TX_STATE_READY;
}
void SERIAL_send_uart_bytes(const uint8_t * buf, uint16_t len) {
while (len--) {
*ptrTxISR++ = *buf++;
serialTxBufferCount++;
}
}
#if 0
void SERIAL_transmitBuffer(uint8_t len) {
serialTxBufferCount = len;
ptrTxISR = serialTxBuffer;
//UCSR0B |= (1 << UDRIE0); // enable UDRE0 interrupt
serialTxState = TX_STATE_READY;
}
#endif
void SERIAL_startTX(void) {
if (serialTxState == TX_STATE_READY) {
serialTxState = TX_STATE_BUSY;
UCSR0B |= (1 << UDRIE0); // enable UDRE0 interrupt
}
}
static void uart_4800(void) {
#ifndef SIMU
#undef BAUD // avoid compiler warning
#define BAUD 4800
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
#endif
}
static void uart_9600(void) {
#ifndef SIMU
#undef BAUD // avoid compiler warning
#define BAUD 9600
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
#endif
}
static void uart_14400(void) {
#ifndef SIMU
#undef BAUD // avoid compiler warning
#define BAUD 14400
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
#endif
}
static void uart_19200(void) {
#ifndef SIMU
#undef BAUD // avoid compiler warning
#define BAUD 19200
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
#endif
}
static void uart_38400(void) {
#ifndef SIMU
#undef BAUD // avoid compiler warning
#define BAUD 38400
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
#endif
}
static void uart_57600(void) {
#ifndef SIMU
#undef BAUD // avoid compiler warning
#define BAUD 57600
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
#endif
}
static void uart_76800(void) {
#ifndef SIMU
#undef BAUD // avoid compiler warning
#define BAUD 76800
#include <util/setbaud.h>
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
#endif
}
inline void SERIAL_EnableTXD(void) {
//UCSR0B |= (1 << TXEN0); // enable TX
UCSR0B |= (1 << TXEN0) | (1 << UDRIE0); // enable TX and TX interrupt
}
#if 0
void SERIAL_DisableTXD(void) {
UCSR0B &= ~(1 << TXEN0); // disable TX
UCSR0B &= ~(1 << UDRIE0); // disable Interrupt
}
#endif
void SERIAL_Init(void) {
DDRE &= ~(1 << DDE0); // set RXD0 pin as input
PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin
switch (g_eeGeneral.mavbaud) {
case BAUD_4800:
uart_4800();
break;
case BAUD_9600:
uart_9600();
break;
case BAUD_14400:
uart_14400();
break;
case BAUD_19200:
uart_19200();
break;
case BAUD_38400:
uart_38400();
break;
case BAUD_57600:
uart_57600();
break;
case BAUD_76800:
uart_76800();
break;
}
// UCSR0A &= ~(1 << U2X0); // disable double speed operation
// set 8N1
UCSR0B = 0 | (0 << RXCIE0) | (0 << TXCIE0) | (0 << UDRIE0) | (0 << RXEN0) | (0 << TXEN0) | (0 << UCSZ02);
UCSR0C = 0 | (1 << UCSZ01) | (1 << UCSZ00);
#if !defined(SIMU)
while (UCSR0A & (1 << RXC0)) {
UDR0; // flush receive buffer
}
#endif
SERIAL_EnableTXD();
SERIAL_EnableRXD();
}

View file

@ -1,65 +0,0 @@
/*
* Copyright (C) OpenTX
*
* Based on code named
* th9x - http://code.google.com/p/th9x
* er9x - http://code.google.com/p/er9x
* gruvin9x - http://code.google.com/p/gruvin9x
*
* License GPLv2: http://www.gnu.org/licenses/gpl-2.0.html
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License version 2 as
* published by the Free Software Foundation.
*
* This program 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.
*/
#ifndef _SERIAL_DRIVER_H_
#define _SERIAL_DRIVER_H_
#include <inttypes.h>
typedef enum serial_tx_state_ {
TX_STATE_EMPTY = 0, //
TX_STATE_READY, //
TX_STATE_BUSY
} serial_tx_state_t;
extern serial_tx_state_t serialTxState;
//! \brief Baudrate selection.
enum SERIAL_BAUDS {
BAUD_4800 = 0,
BAUD_9600,
BAUD_14400,
BAUD_19200,
BAUD_38400,
BAUD_57600,
BAUD_76800
};
//! \brief Definition of baudrate settings item choices.
typedef void (*SerialFuncP)(uint8_t event);
extern SerialFuncP RXHandler;
#define MAX_TX_BUFFER 32
//#if 0
extern uint8_t serialTxBuffer[MAX_TX_BUFFER]; // 32 characters
extern uint8_t serialTxBufferCount;
extern uint8_t * ptrTxISR;
//#endif
void SERIAL_Init(void);
//void SERIAL_transmitBuffer(uint8_t len);
extern void SERIAL_start_uart_send();
extern void SERIAL_end_uart_send();
extern void SERIAL_send_uart_bytes(uint8_t * buf, uint16_t len);
void SERIAL_startTX(void);
#define IS_TX_BUSY (serialTxState!=TX_STATE_EMPTY)
#endif // _SERIAL_DRIVER_H_

View file

@ -16,11 +16,22 @@
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
*
*/ */
#include "opentx.h" #include "opentx.h"
#if defined(TELEMETRY_FRSKY) #if defined(TELEMETRY_FRSKY) || defined(TELEMETRY_MAVLINK)
enum SERIAL_BAUDS {// KEEP IN SYNC WITH GUI
BAUD_4800 = 0,
BAUD_9600,
BAUD_14400,
BAUD_19200,
BAUD_38400,
BAUD_57600,
BAUD_76800
};
void telemetryEnableTx(void) void telemetryEnableTx(void)
{ {
@ -33,6 +44,9 @@ void telemetryEnableRx(void)
UCSRB_N(TLM_USART) |= (1 << RXCIE_N(TLM_USART)); // enable Interrupt UCSRB_N(TLM_USART) |= (1 << RXCIE_N(TLM_USART)); // enable Interrupt
} }
void processSerialData(uint8_t data);
extern uint8_t telemetryRxBufferCount;
ISR(USART_RX_vect_N(TLM_USART)) ISR(USART_RX_vect_N(TLM_USART))
{ {
uint8_t stat; uint8_t stat;
@ -79,26 +93,168 @@ ISR(USART_RX_vect_N(TLM_USART))
telemetryRxBufferCount = 0; telemetryRxBufferCount = 0;
} }
else { else {
processFrskyTelemetryData(data); processSerialData(data);
} }
cli() ; cli() ;
UCSRB_N(TLM_USART) |= (1 << RXCIE_N(TLM_USART)); // enable Interrupt UCSRB_N(TLM_USART) |= (1 << RXCIE_N(TLM_USART)); // enable Interrupt
} }
void telemetryPortInit() static void uart_4800(void) {
#undef BAUD
#define BAUD 4800
#include <util/setbaud.h>
UBRRH_N(TLM_USART) = UBRRH_VALUE;
UBRRL_N(TLM_USART) = UBRRL_VALUE;
#if defined USE_2X
UCSRA_N(TLM_USART) |= (1 << U2X_N(TLM_USART)); // enable double speed operation.
#else
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
#endif
}
static void uart_9600(void) {
#undef BAUD
#define BAUD 9600
#include <util/setbaud.h>
UBRRH_N(TLM_USART) = UBRRH_VALUE;
UBRRL_N(TLM_USART) = UBRRL_VALUE;
#if defined USE_2X
UCSRA_N(TLM_USART) |= (1 << U2X_N(TLM_USART)); // enable double speed operation.
#else
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
#endif
}
static void uart_14400(void) {
#undef BAUD
#define BAUD 14400
#include <util/setbaud.h>
UBRRH_N(TLM_USART) = UBRRH_VALUE;
UBRRL_N(TLM_USART) = UBRRL_VALUE;
#if defined USE_2X
UCSRA_N(TLM_USART) |= (1 << U2X_N(TLM_USART)); // enable double speed operation.
#else
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
#endif
}
static void uart_19200(void) {
#undef BAUD
#define BAUD 19200
#include <util/setbaud.h>
UBRRH_N(TLM_USART) = UBRRH_VALUE;
UBRRL_N(TLM_USART) = UBRRL_VALUE;
#if defined USE_2X
UCSRA_N(TLM_USART) |= (1 << U2X_N(TLM_USART)); // enable double speed operation.
#else
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
#endif
}
static void uart_38400(void) {
#undef BAUD
#define BAUD 38400
#include <util/setbaud.h>
UBRRH_N(TLM_USART) = UBRRH_VALUE;
UBRRL_N(TLM_USART) = UBRRL_VALUE;
#if defined USE_2X
UCSRA_N(TLM_USART) |= (1 << U2X_N(TLM_USART)); // enable double speed operation.
#else
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
#endif
}
static void uart_57600(void) {
#undef BAUD
#define BAUD 57600
#include <util/setbaud.h>
UBRRH_N(TLM_USART) = UBRRH_VALUE;
UBRRL_N(TLM_USART) = UBRRL_VALUE;
#if defined USE_2X
UCSRA_N(TLM_USART) |= (1 << U2X_N(TLM_USART)); // enable double speed operation.
#else
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
#endif
}
static void uart_76800(void) {
#undef BAUD
#define BAUD 76800
#include <util/setbaud.h>
UBRRH_N(TLM_USART) = UBRRH_VALUE;
UBRRL_N(TLM_USART) = UBRRL_VALUE;
#if defined USE_2X
UCSRA_N(TLM_USART) |= (1 << U2X_N(TLM_USART)); // enable double speed operation.
#else
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
#endif
}
void telemetryPortInitFromIndex(uint8_t index) {
switch (index) {
case BAUD_4800:
telemetryPortInit(4800);
break;
case BAUD_9600:
telemetryPortInit(9600);
break;
case BAUD_14400:
telemetryPortInit(14400);
break;
case BAUD_19200:
telemetryPortInit(19200);
break;
case BAUD_38400:
telemetryPortInit(38400);
break;
case BAUD_57600:
telemetryPortInit(57600);
break;
case BAUD_76800:
telemetryPortInit(76800);
break;
}
}
void telemetryPortInit() {
telemetryPortInit(9600);
}
void telemetryPortInit(uint32_t baudrate)
{ {
#if !defined(SIMU) #if !defined(SIMU)
RXD_DDR_N(TLM_USART) &= ~(1 << RXD_DDR_PIN_N(TLM_USART)); // set RXD pin as input RXD_DDR_N(TLM_USART) &= ~(1 << RXD_DDR_PIN_N(TLM_USART)); // set RXD pin as input
RXD_PORT_N(TLM_USART) &= ~(1 << RXD_PORT_PIN_N(TLM_USART)); // disable pullup on RXD pin RXD_PORT_N(TLM_USART) &= ~(1 << RXD_PORT_PIN_N(TLM_USART)); // disable pullup on RXD pin
switch (baudrate) {
#undef BAUD case 4800:
#define BAUD 9600 uart_4800();
#include <util/setbaud.h> break;
case 9600:
UBRRH_N(TLM_USART) = UBRRH_VALUE; uart_9600();
UBRRL_N(TLM_USART) = UBRRL_VALUE; break;
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation. case 14400:
uart_14400();
break;
case 19200:
uart_19200();
break;
case 38400:
uart_38400();
break;
case 57600:
uart_57600();
break;
case 58798:
uart_58798();
break;
case 76800:
uart_76800();
break;
default:
uart_57600();
break;
}
// set 8N1 // set 8N1
UCSRB_N(TLM_USART) = 0 | (0 << RXCIE_N(TLM_USART)) | (0 << TXCIE_N(TLM_USART)) | (0 << UDRIE_N(TLM_USART)) | (0 << RXEN_N(TLM_USART)) | (0 << TXEN_N(TLM_USART)) | (0 << UCSZ2_N(TLM_USART)); UCSRB_N(TLM_USART) = 0 | (0 << RXCIE_N(TLM_USART)) | (0 << TXCIE_N(TLM_USART)) | (0 << UDRIE_N(TLM_USART)) | (0 << RXEN_N(TLM_USART)) | (0 << TXEN_N(TLM_USART)) | (0 << UCSZ2_N(TLM_USART));
@ -108,9 +264,9 @@ void telemetryPortInit()
while (UCSRA_N(TLM_USART) & (1 << RXC_N(TLM_USART))) UDR_N(TLM_USART); // flush receive buffer while (UCSRA_N(TLM_USART) & (1 << RXC_N(TLM_USART))) UDR_N(TLM_USART); // flush receive buffer
// These should be running right from power up on a FrSky enabled '9X. // These should be running right from power up on a FrSky enabled '9X.
#if defined(TELEMETRY_FRSKY)
telemetryEnableTx(); // enable FrSky-Telemetry emission telemetryEnableTx(); // enable FrSky-Telemetry emission
frskyTxBufferCount = 0; // TODO not driver code #endif
telemetryEnableRx(); // enable FrSky-Telemetry reception telemetryEnableRx(); // enable FrSky-Telemetry reception
#endif #endif
} }

View file

@ -48,7 +48,7 @@ enum FrSkyDataState {
#endif #endif
}; };
NOINLINE void processFrskyTelemetryData(uint8_t data) NOINLINE void processSerialData(uint8_t data)
{ {
static uint8_t dataState = STATE_DATA_IDLE; static uint8_t dataState = STATE_DATA_IDLE;

View file

@ -479,6 +479,6 @@ void frskySetCellVoltage(uint8_t battnumber, frskyCellVoltage_t cellVolts);
void frskyUpdateCells(); void frskyUpdateCells();
#endif #endif
void processFrskyTelemetryData(uint8_t data); void processSerialData(uint8_t data);
#endif // _FRSKY_H_ #endif // _FRSKY_H_

View file

@ -29,7 +29,6 @@
#define MAVLINK_COMM_NUM_BUFFERS 1 #define MAVLINK_COMM_NUM_BUFFERS 1
#include "GCS_MAVLink/include_v1.0/mavlink_types.h" #include "GCS_MAVLink/include_v1.0/mavlink_types.h"
#include "targets/common/avr/serial_driver.h"
#include "opentx.h" #include "opentx.h"
extern int8_t mav_heartbeat; extern int8_t mav_heartbeat;

View file

@ -82,7 +82,7 @@ void processTelemetryData(uint8_t data)
return; return;
} }
#endif #endif
processFrskyTelemetryData(data); processSerialData(data);
} }
#endif #endif
@ -115,7 +115,7 @@ void telemetryWakeup()
if (telemetryProtocol == PROTOCOL_FRSKY_D_SECONDARY) { if (telemetryProtocol == PROTOCOL_FRSKY_D_SECONDARY) {
uint8_t data; uint8_t data;
while (telemetrySecondPortReceive(data)) { while (telemetrySecondPortReceive(data)) {
processFrskyTelemetryData(data); processSerialData(data);
} }
} }
else { else {