mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Update serial port handling for boards with only 2 ports.
This commit is contained in:
parent
5871f90465
commit
dc0f461c73
13 changed files with 76 additions and 69 deletions
|
@ -34,6 +34,8 @@
|
|||
#include <stdarg.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
|
|
|
@ -86,7 +86,7 @@ static uint32_t flashWriteAddress = (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE *
|
|||
master_t masterConfig; // master config struct with data independent from profiles
|
||||
profile_t currentProfile; // profile config struct
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 74;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 75;
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
|
@ -191,12 +191,15 @@ void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
|
|||
|
||||
void resetSerialConfig(serialConfig_t *serialConfig)
|
||||
{
|
||||
serialConfig->serial_port_1_scenario = lookupScenarioIndex(SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH);
|
||||
serialConfig->serial_port_2_scenario = lookupScenarioIndex(SCENARIO_GPS_ONLY);
|
||||
serialConfig->serial_port_3_scenario = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
serialConfig->serial_port_4_scenario = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
#ifdef STM32F303xC
|
||||
serialConfig->serial_port_5_scenario = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
serialConfig->serial_port_scenario[0] = lookupScenarioIndex(SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH);
|
||||
serialConfig->serial_port_scenario[1] = lookupScenarioIndex(SCENARIO_GPS_ONLY);
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
serialConfig->serial_port_scenario[2] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
serialConfig->serial_port_scenario[3] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
|
||||
#if (SERIAL_PORT_COUNT > 4)
|
||||
serialConfig->serial_port_scenario[4] = lookupScenarioIndex(SCENARIO_UNUSED);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
serialConfig->msp_baudrate = 115200;
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SOFT_SERIAL
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "system.h"
|
||||
|
@ -429,3 +431,5 @@ const struct serialPortVTable softSerialVTable[] = {
|
|||
softSerialSetMode,
|
||||
}
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -69,16 +69,16 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
|||
{SERIAL_PORT_USB_VCP, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART4, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
};
|
||||
|
||||
const static serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE },
|
||||
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
{SERIAL_PORT_USART3, 9600, 19200, SPF_SUPPORTS_CALLBACK},
|
||||
{SERIAL_PORT_USART4, 9600, 19200, SPF_SUPPORTS_CALLBACK}
|
||||
};
|
||||
|
||||
#else
|
||||
|
@ -86,31 +86,31 @@ const static serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
|||
#ifdef CC3D
|
||||
static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
};
|
||||
|
||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE },
|
||||
{SERIAL_PORT_USART3, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
{SERIAL_PORT_USART3, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE}
|
||||
};
|
||||
#else
|
||||
|
||||
static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART2, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
#endif
|
||||
};
|
||||
|
||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE },
|
||||
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE},
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
#endif
|
||||
|
@ -167,15 +167,17 @@ static serialPortIndex_e lookupSerialPortIndexByIdentifier(serialPortIdentifier_
|
|||
return portIndex;
|
||||
}
|
||||
|
||||
#define IDENTIFIER_NOT_FOUND 0xFF
|
||||
|
||||
static uint8_t lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier_e identifier)
|
||||
{
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
if (serialPortFunctions[index].identifier == identifier) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
return index;
|
||||
}
|
||||
}
|
||||
return IDENTIFIER_NOT_FOUND;
|
||||
}
|
||||
|
||||
static const functionConstraint_t *findFunctionConstraint(serialPortFunction_e function)
|
||||
|
@ -225,12 +227,14 @@ serialPortSearchResult_t *findNextSerialPort(serialPortFunction_e function, cons
|
|||
uint8_t serialPortIndex = lookupSerialPortIndexByIdentifier(serialPortFunction->identifier);
|
||||
const serialPortConstraint_t *serialPortConstraint = &serialPortConstraints[serialPortIndex];
|
||||
|
||||
#ifdef USE_SOFT_SERIAL
|
||||
if (!feature(FEATURE_SOFTSERIAL) && (
|
||||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1 ||
|
||||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2
|
||||
)) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (functionConstraint->requiredSerialPortFeatures != SPF_NONE) {
|
||||
if (!(serialPortConstraint->feature & functionConstraint->requiredSerialPortFeatures)) {
|
||||
|
@ -468,26 +472,15 @@ bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t fun
|
|||
|
||||
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
|
||||
{
|
||||
#ifdef STM32F303xC
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USB_VCP)].scenario = serialPortScenarios[serialConfig->serial_port_1_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART1)].scenario = serialPortScenarios[serialConfig->serial_port_2_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART2)].scenario = serialPortScenarios[serialConfig->serial_port_3_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL1)].scenario = serialPortScenarios[serialConfig->serial_port_4_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL2)].scenario = serialPortScenarios[serialConfig->serial_port_5_scenario];
|
||||
#else
|
||||
uint32_t portIndex = 0, serialPortIdentifier;
|
||||
|
||||
#ifdef CC3D
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART1)].scenario = serialPortScenarios[serialConfig->serial_port_1_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART3)].scenario = serialPortScenarios[serialConfig->serial_port_2_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL1)].scenario = serialPortScenarios[serialConfig->serial_port_3_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL2)].scenario = serialPortScenarios[serialConfig->serial_port_4_scenario];
|
||||
#else
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART1)].scenario = serialPortScenarios[serialConfig->serial_port_1_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_USART2)].scenario = serialPortScenarios[serialConfig->serial_port_2_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL1)].scenario = serialPortScenarios[serialConfig->serial_port_3_scenario];
|
||||
serialPortFunctions[lookupSerialPortFunctionIndexByIdentifier(SERIAL_PORT_SOFTSERIAL2)].scenario = serialPortScenarios[serialConfig->serial_port_4_scenario];
|
||||
#endif
|
||||
#endif
|
||||
for (serialPortIdentifier = 0; serialPortIdentifier < SERIAL_PORT_IDENTIFIER_COUNT && portIndex < SERIAL_PORT_COUNT; serialPortIdentifier++) {
|
||||
uint32_t functionIndex = lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier);
|
||||
if (functionIndex == IDENTIFIER_NOT_FOUND) {
|
||||
continue;
|
||||
}
|
||||
serialPortFunctions[functionIndex].scenario = serialPortScenarios[serialConfig->serial_port_scenario[portIndex++]];
|
||||
}
|
||||
}
|
||||
|
||||
serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion)
|
||||
|
@ -541,7 +534,7 @@ serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbac
|
|||
serialPort = uartOpen(USART3, callback, baudRate, mode, inversion);
|
||||
break;
|
||||
#endif
|
||||
#ifdef SOFT_SERIAL
|
||||
#ifdef USE_SOFT_SERIAL
|
||||
case SERIAL_PORT_SOFTSERIAL1:
|
||||
serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, inversion);
|
||||
serialSetMode(serialPort, mode);
|
||||
|
|
|
@ -57,37 +57,32 @@ typedef enum {
|
|||
#define SERIAL_PORT_SCENARIO_MAX (SERIAL_PORT_SCENARIO_COUNT - 1)
|
||||
extern const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT];
|
||||
|
||||
|
||||
#ifdef STM32F303xC
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
typedef enum {
|
||||
SERIAL_PORT_1 = 0,
|
||||
SERIAL_PORT_2,
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
SERIAL_PORT_3,
|
||||
SERIAL_PORT_4,
|
||||
#if (SERIAL_PORT_COUNT > 4)
|
||||
SERIAL_PORT_5
|
||||
#endif
|
||||
#endif
|
||||
} serialPortIndex_e;
|
||||
|
||||
|
||||
#ifdef STM32F303xC
|
||||
|
||||
typedef enum {
|
||||
SERIAL_PORT_USB_VCP = 0,
|
||||
SERIAL_PORT_USART1,
|
||||
SERIAL_PORT_USART2,
|
||||
SERIAL_PORT_SOFTSERIAL1,
|
||||
SERIAL_PORT_SOFTSERIAL2
|
||||
SERIAL_PORT_USART3,
|
||||
SERIAL_PORT_USART4
|
||||
} serialPortIdentifier_e;
|
||||
|
||||
#define SERIAL_PORT_IDENTIFIER_COUNT 5
|
||||
#else
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
typedef enum {
|
||||
SERIAL_PORT_1 = 0,
|
||||
SERIAL_PORT_2,
|
||||
SERIAL_PORT_3,
|
||||
SERIAL_PORT_4
|
||||
} serialPortIndex_e;
|
||||
|
||||
typedef enum {
|
||||
SERIAL_PORT_USART1 = 0,
|
||||
SERIAL_PORT_USART2,
|
||||
|
@ -96,6 +91,7 @@ typedef enum {
|
|||
SERIAL_PORT_SOFTSERIAL2
|
||||
} serialPortIdentifier_e;
|
||||
|
||||
#define SERIAL_PORT_IDENTIFIER_COUNT 5
|
||||
#endif
|
||||
|
||||
// bitmask
|
||||
|
@ -126,13 +122,7 @@ typedef struct serialPortFunctionList_s {
|
|||
} serialPortFunctionList_t;
|
||||
|
||||
typedef struct serialConfig_s {
|
||||
uint8_t serial_port_1_scenario;
|
||||
uint8_t serial_port_2_scenario;
|
||||
uint8_t serial_port_3_scenario;
|
||||
uint8_t serial_port_4_scenario;
|
||||
#ifdef STM32F303xC
|
||||
uint8_t serial_port_5_scenario;
|
||||
#endif
|
||||
uint8_t serial_port_scenario[SERIAL_PORT_COUNT];
|
||||
uint32_t msp_baudrate;
|
||||
uint32_t cli_baudrate;
|
||||
uint32_t gps_baudrate;
|
||||
|
|
|
@ -206,12 +206,14 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE | MASTER_VALUE, &masterConfig.fixedwing_althold_dir, -1, 1 },
|
||||
|
||||
{ "serial_port_1_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_1_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_2_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_2_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_3_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_3_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_4_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_4_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_1_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[0], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_2_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[1], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#if (SERIAL_PORT_COUNT > 2)
|
||||
{ "serial_port_3_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[2], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_4_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[3], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#if (SERIAL_PORT_COUNT > 4)
|
||||
{ "serial_port_5_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_5_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_5_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[4], 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#endif
|
||||
#endif
|
||||
|
||||
{ "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
||||
|
|
|
@ -34,20 +34,20 @@
|
|||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_USART1
|
||||
|
||||
#define USE_USART3
|
||||
|
||||
#define USART3_RX_PIN Pin_11
|
||||
#define USART3_TX_PIN Pin_10
|
||||
#define USART3_GPIO GPIOB
|
||||
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
|
||||
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
|
||||
|
||||
#define SERIAL_PORT_COUNT 2
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
|
|
@ -40,6 +40,8 @@
|
|||
#define LED0
|
||||
#define LED1
|
||||
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
|
|
@ -40,6 +40,8 @@
|
|||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
||||
#define SERIAL_PORT_COUNT 2
|
||||
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
// #define SOFT_I2C // enable to test software i2c
|
||||
|
|
|
@ -49,6 +49,9 @@
|
|||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_SOFT_SERIAL
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
|
|
|
@ -30,6 +30,8 @@
|
|||
#define GYRO
|
||||
#define ACC
|
||||
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
|
|
@ -42,6 +42,8 @@
|
|||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_SOFT_SERIAL
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
|
|
|
@ -42,6 +42,8 @@
|
|||
#define LED0
|
||||
#define LED1
|
||||
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue