Skip to content

Commit

Permalink
Merge pull request #6487 from iNavFlight/de_remove_uib
Browse files Browse the repository at this point in the history
Remove unused UAV_INTERCONNECT
  • Loading branch information
digitalentity authored Jan 9, 2021
2 parents 4d0a3fe + ef34fc2 commit 0b387d6
Show file tree
Hide file tree
Showing 18 changed files with 8 additions and 1,040 deletions.
6 changes: 0 additions & 6 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -406,8 +406,6 @@ main_sources(COMMON_SRC
rx/sumd.h
rx/sumh.c
rx/sumh.h
rx/uib_rx.c
rx/uib_rx.h
rx/xbus.c
rx/xbus.h

Expand Down Expand Up @@ -435,10 +433,6 @@ main_sources(COMMON_SRC
sensors/temperature.c
sensors/temperature.h

uav_interconnect/uav_interconnect.h
uav_interconnect/uav_interconnect_bus.c
uav_interconnect/uav_interconnect_rangefinder.c

blackbox/blackbox.c
blackbox/blackbox.h
blackbox/blackbox_encoding.c
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/opflow/opflow_virtual.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
*/

/*
* This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB)
* This is a bridge driver between a sensor reader that operates at high level (i.e. on top of UART)
*/

#include <stdbool.h>
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/rangefinder/rangefinder_virtual.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
*/

/*
* This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB)
* This is a bridge driver between a sensor reader that operates at high level (i.e. on top of UART)
*/

#include <stdbool.h>
Expand Down
6 changes: 0 additions & 6 deletions src/main/fc/fc_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,6 @@

#include "telemetry/telemetry.h"

#include "uav_interconnect/uav_interconnect.h"

#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
Expand Down Expand Up @@ -570,10 +568,6 @@ void init(void)
}
#endif

#ifdef USE_UAV_INTERCONNECT
uavInterconnectBusInit();
#endif

#if defined(USE_CMS) && defined(USE_SPEKTRUM_CMS_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
// Register the srxl Textgen telemetry sensor as a displayport device
cmsDisplayPortRegister(displayPortSrxlInit());
Expand Down
16 changes: 1 addition & 15 deletions src/main/fc/fc_tasks.c
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,6 @@

#include "config/feature.h"

#include "uav_interconnect/uav_interconnect.h"

void taskHandleSerial(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
Expand Down Expand Up @@ -365,9 +363,6 @@ void fcTasksInit(void)
setTaskEnabled(TASK_VTXCTRL, true);
#endif
#endif
#ifdef USE_UAV_INTERCONNECT
setTaskEnabled(TASK_UAV_INTERCONNECT, uavInterconnectBusIsInitialized());
#endif
#ifdef USE_RCDEVICE
setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled());
#endif
Expand Down Expand Up @@ -572,16 +567,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
[TASK_OPFLOW] = {
.taskName = "OPFLOW",
.taskFunc = taskUpdateOpticalFlow,
.desiredPeriod = TASK_PERIOD_HZ(100), // I2C/SPI sensor will work at higher rate and accumulate, UIB/UART sensor will work at lower rate w/o accumulation
.staticPriority = TASK_PRIORITY_MEDIUM,
},
#endif

#ifdef USE_UAV_INTERCONNECT
[TASK_UAV_INTERCONNECT] = {
.taskName = "UIB",
.taskFunc = uavInterconnectBusTask,
.desiredPeriod = 1000000 / 500, // 500 Hz
.desiredPeriod = TASK_PERIOD_HZ(100), // I2C/SPI sensor will work at higher rate and accumulate, UART sensor will work at lower rate w/o accumulation
.staticPriority = TASK_PRIORITY_MEDIUM,
},
#endif
Expand Down
4 changes: 2 additions & 2 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ tables:
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"]
enum: accelerationSensor_e
- name: rangefinder_hardware
values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "BENEWAKE"]
values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UNUSED", "BENEWAKE"]
enum: rangefinderType_e
- name: mag_hardware
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "FAKE"]
Expand All @@ -22,7 +22,7 @@ tables:
values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
enum: pitotSensor_e
- name: receiver_type
values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UIB"]
values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UNUSED"]
enum: rxReceiverType_e
- name: serial_rx
values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST"]
Expand Down
2 changes: 1 addition & 1 deletion src/main/io/serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ typedef enum {
FUNCTION_RCDEVICE = (1 << 10), // 1024
FUNCTION_VTX_SMARTAUDIO = (1 << 11), // 2048
FUNCTION_VTX_TRAMP = (1 << 12), // 4096
FUNCTION_UAV_INTERCONNECT = (1 << 13), // 8192
FUNCTION_UNUSED_1 = (1 << 13), // 8192: former UAV_INTERCONNECT
FUNCTION_OPTICAL_FLOW = (1 << 14), // 16384
FUNCTION_LOG = (1 << 15), // 32768
FUNCTION_RANGEFINDER = (1 << 16), // 65536
Expand Down
7 changes: 0 additions & 7 deletions src/main/rx/rx.c
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,6 @@
#include "rx/srxl2.h"
#include "rx/sumd.h"
#include "rx/sumh.h"
#include "rx/uib_rx.h"
#include "rx/xbus.h"
#include "rx/ghst.h"

Expand Down Expand Up @@ -330,12 +329,6 @@ void rxInit(void)
break;
#endif

#ifdef USE_RX_UIB
case RX_TYPE_UIB:
rxUIBInit(rxConfig(), &rxRuntimeConfig);
break;
#endif

#ifdef USE_RX_SPI
case RX_TYPE_SPI:
if (!rxSpiInit(rxConfig(), &rxRuntimeConfig)) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/rx/rx.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ typedef enum {
RX_TYPE_SERIAL = 2,
RX_TYPE_MSP = 3,
RX_TYPE_SPI = 4,
RX_TYPE_UIB = 5
RX_TYPE_UNUSED_1 = 5
} rxReceiverType_e;

typedef enum {
Expand Down
126 changes: 0 additions & 126 deletions src/main/rx/uib_rx.c

This file was deleted.

31 changes: 0 additions & 31 deletions src/main/rx/uib_rx.h

This file was deleted.

3 changes: 0 additions & 3 deletions src/main/scheduler/scheduler.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,9 +101,6 @@ typedef enum {
#ifdef USE_OPFLOW
TASK_OPFLOW,
#endif
#ifdef USE_UAV_INTERCONNECT
TASK_UAV_INTERCONNECT,
#endif
#ifdef USE_RCDEVICE
TASK_RCDEVICE,
#endif
Expand Down
11 changes: 0 additions & 11 deletions src/main/sensors/rangefinder.c
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,6 @@

#include "scheduler/scheduler.h"

#include "uav_interconnect/uav_interconnect.h"

rangefinder_t rangefinder;

#define RANGEFINDER_HARDWARE_TIMEOUT_MS 500 // Accept 500ms of non-responsive sensor, report HW failure otherwise
Expand Down Expand Up @@ -142,15 +140,6 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar
#endif
break;

case RANGEFINDER_UIB:
#if defined(USE_RANGEFINDER_UIB)
if (uibRangefinderDetect(dev)) {
rangefinderHardware = RANGEFINDER_UIB;
rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_UIB_TASK_PERIOD_MS));
}
#endif
break;

case RANGEFINDER_BENEWAKE:
#if defined(USE_RANGEFINDER_BENEWAKE)
if (virtualRangefinderDetect(dev, &rangefinderBenewakeVtable)) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/sensors/rangefinder.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ typedef enum {
RANGEFINDER_HCSR04I2C = 3,
RANGEFINDER_VL53L0X = 4,
RANGEFINDER_MSP = 5,
RANGEFINDER_UIB = 6,
RANGEFINDER_UNUSED = 6, // Was UIB
RANGEFINDER_BENEWAKE = 7,
} rangefinderType_e;

Expand Down
2 changes: 0 additions & 2 deletions src/main/target/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,6 @@
#define USE_DYNAMIC_FILTERS
#define USE_GYRO_KALMAN
#define USE_EXTENDED_CMS_MENUS
#define USE_UAV_INTERCONNECT
#define USE_RX_UIB
#define USE_HOTT_TEXTMODE

// NAZA GPS support for F4+ only
Expand Down
Loading

0 comments on commit 0b387d6

Please sign in to comment.