mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
Disabled extra (ESC) sensors in SmartPort by default.
This commit is contained in:
parent
6784ed9335
commit
1286e400d8
4 changed files with 11 additions and 7 deletions
|
@ -872,6 +872,9 @@ const clivalue_t valueTable[] = {
|
||||||
#if defined(USE_TELEMETRY_IBUS)
|
#if defined(USE_TELEMETRY_IBUS)
|
||||||
{ "ibus_sensor", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = IBUS_SENSOR_COUNT, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, flysky_sensors)},
|
{ "ibus_sensor", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = IBUS_SENSOR_COUNT, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, flysky_sensors)},
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(USE_TELEMETRY_SMARTPORT)
|
||||||
|
{ "smartport_use_extra_sensors", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, smartport_use_extra_sensors)},
|
||||||
|
#endif
|
||||||
#endif // USE_TELEMETRY
|
#endif // USE_TELEMETRY
|
||||||
|
|
||||||
// PG_LED_STRIP_CONFIG
|
// PG_LED_STRIP_CONFIG
|
||||||
|
|
|
@ -169,12 +169,11 @@ typedef struct frSkyTableInfo_s {
|
||||||
|
|
||||||
static frSkyTableInfo_t frSkyDataIdTableInfo = { frSkyDataIdTable, 0, 0 };
|
static frSkyTableInfo_t frSkyDataIdTableInfo = { frSkyDataIdTable, 0, 0 };
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
#define ESC_DATAID_COUNT sizeof(frSkyEscDataIdTable)/sizeof(uint16_t)
|
#define ESC_DATAID_COUNT ( sizeof(frSkyEscDataIdTable) / sizeof(uint16_t) )
|
||||||
|
|
||||||
static frSkyTableInfo_t frSkyEscDataIdTableInfo = {frSkyEscDataIdTable, ESC_DATAID_COUNT, 0};
|
static frSkyTableInfo_t frSkyEscDataIdTableInfo = {frSkyEscDataIdTable, ESC_DATAID_COUNT, 0};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define __USE_C99_MATH // for roundf()
|
|
||||||
#define SMARTPORT_BAUD 57600
|
#define SMARTPORT_BAUD 57600
|
||||||
#define SMARTPORT_UART_MODE MODE_RXTX
|
#define SMARTPORT_UART_MODE MODE_RXTX
|
||||||
#define SMARTPORT_SERVICE_TIMEOUT_MS 1 // max allowed time to find a value to send
|
#define SMARTPORT_SERVICE_TIMEOUT_MS 1 // max allowed time to find a value to send
|
||||||
|
@ -329,7 +328,7 @@ static void initSmartPortSensors(void)
|
||||||
|
|
||||||
if (isBatteryVoltageConfigured()) {
|
if (isBatteryVoltageConfigured()) {
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
if (!feature(FEATURE_ESC_SENSOR)) {
|
if (!feature(FEATURE_ESC_SENSOR) || !telemetryConfig()->smartport_use_extra_sensors) {
|
||||||
#endif
|
#endif
|
||||||
ADD_SENSOR(FSSP_DATAID_VFAS);
|
ADD_SENSOR(FSSP_DATAID_VFAS);
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
|
@ -340,7 +339,7 @@ static void initSmartPortSensors(void)
|
||||||
|
|
||||||
if (isAmperageConfigured()) {
|
if (isAmperageConfigured()) {
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
if (!feature(FEATURE_ESC_SENSOR)) {
|
if (!feature(FEATURE_ESC_SENSOR) || !telemetryConfig()->smartport_use_extra_sensors) {
|
||||||
#endif
|
#endif
|
||||||
ADD_SENSOR(FSSP_DATAID_CURRENT);
|
ADD_SENSOR(FSSP_DATAID_CURRENT);
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
|
@ -375,7 +374,7 @@ static void initSmartPortSensors(void)
|
||||||
frSkyDataIdTableInfo.index = 0;
|
frSkyDataIdTableInfo.index = 0;
|
||||||
|
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
if (feature(FEATURE_ESC_SENSOR)) {
|
if (feature(FEATURE_ESC_SENSOR && telemetryConfig()->smartport_use_extra_sensors)) {
|
||||||
frSkyEscDataIdTableInfo.size = ESC_DATAID_COUNT;
|
frSkyEscDataIdTableInfo.size = ESC_DATAID_COUNT;
|
||||||
} else {
|
} else {
|
||||||
frSkyEscDataIdTableInfo.size = 0;
|
frSkyEscDataIdTableInfo.size = 0;
|
||||||
|
|
|
@ -75,7 +75,8 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
|
||||||
IBUS_SENSOR_TYPE_TEMPERATURE,
|
IBUS_SENSOR_TYPE_TEMPERATURE,
|
||||||
IBUS_SENSOR_TYPE_RPM_FLYSKY,
|
IBUS_SENSOR_TYPE_RPM_FLYSKY,
|
||||||
IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE
|
IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE
|
||||||
}
|
},
|
||||||
|
.smartport_use_extra_sensors = false,
|
||||||
);
|
);
|
||||||
|
|
||||||
void telemetryInit(void)
|
void telemetryInit(void)
|
||||||
|
|
|
@ -53,6 +53,7 @@ typedef struct telemetryConfig_s {
|
||||||
uint8_t pidValuesAsTelemetry;
|
uint8_t pidValuesAsTelemetry;
|
||||||
uint8_t report_cell_voltage;
|
uint8_t report_cell_voltage;
|
||||||
uint8_t flysky_sensors[IBUS_SENSOR_COUNT];
|
uint8_t flysky_sensors[IBUS_SENSOR_COUNT];
|
||||||
|
uint8_t smartport_use_extra_sensors;
|
||||||
} telemetryConfig_t;
|
} telemetryConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(telemetryConfig_t, telemetryConfig);
|
PG_DECLARE(telemetryConfig_t, telemetryConfig);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue