mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-22 07:45:24 +03:00
Merge pull request #8032 from iNavFlight/dzikuvx-drop-pca9685
Drop PCA9685 support
This commit is contained in:
commit
4fbc0f2e51
48 changed files with 9 additions and 336 deletions
|
@ -5374,7 +5374,7 @@ Selects the servo PWM output cutoff frequency. Value is in [Hz]
|
|||
|
||||
### servo_protocol
|
||||
|
||||
An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port)
|
||||
An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SBUS` (S.Bus protocol output via a configured serial port)
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
|
|
|
@ -180,8 +180,6 @@ main_sources(COMMON_SRC
|
|||
drivers/flash_m25p16.h
|
||||
drivers/io.c
|
||||
drivers/io.h
|
||||
drivers/io_pca9685.c
|
||||
drivers/io_pca9685.h
|
||||
drivers/io_pcf8574.c
|
||||
drivers/io_pcf8574.h
|
||||
drivers/io_port_expander.c
|
||||
|
@ -354,8 +352,6 @@ main_sources(COMMON_SRC
|
|||
io/lights.h
|
||||
io/piniobox.c
|
||||
io/piniobox.h
|
||||
io/pwmdriver_i2c.c
|
||||
io/pwmdriver_i2c.h
|
||||
io/serial.c
|
||||
io/serial.h
|
||||
io/serial_4way.c
|
||||
|
|
|
@ -139,7 +139,6 @@ typedef enum {
|
|||
|
||||
/* Other hardware */
|
||||
DEVHW_MS4525, // Pitot meter
|
||||
DEVHW_PCA9685, // PWM output device
|
||||
DEVHW_M25P16, // SPI NOR flash
|
||||
DEVHW_UG2864, // I2C OLED display
|
||||
DEVHW_SDCARD, // Generic SD-Card
|
||||
|
|
|
@ -1,147 +0,0 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#ifdef USE_PWM_DRIVER_PCA9685
|
||||
|
||||
#include "common/time.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
||||
#define PCA9685_MODE1 0x00
|
||||
#define PCA9685_PRESCALE 0xFE
|
||||
|
||||
#define LED0_ON_L 0x06
|
||||
#define LED0_ON_H 0x07
|
||||
#define LED0_OFF_L 0x08
|
||||
#define LED0_OFF_H 0x09
|
||||
|
||||
#define PCA9685_SERVO_FREQUENCY 60
|
||||
#define PCA9685_SERVO_COUNT 16
|
||||
#define PCA9685_SYNC_THRESHOLD 5
|
||||
|
||||
static busDevice_t * busDev;
|
||||
static uint16_t currentOutputState[PCA9685_SERVO_COUNT] = {0};
|
||||
static uint16_t temporaryOutputState[PCA9685_SERVO_COUNT] = {0};
|
||||
|
||||
void pca9685setPWMOn(uint8_t servoIndex, uint16_t on) {
|
||||
if (servoIndex < PCA9685_SERVO_COUNT) {
|
||||
busWrite(busDev, LED0_ON_L + (servoIndex * 4), on);
|
||||
busWrite(busDev, LED0_ON_H + (servoIndex * 4), on>>8);
|
||||
}
|
||||
}
|
||||
|
||||
void pca9685setPWMOff(uint8_t servoIndex, uint16_t off) {
|
||||
if (servoIndex < PCA9685_SERVO_COUNT) {
|
||||
busWrite(busDev, LED0_OFF_L + (servoIndex * 4), off);
|
||||
busWrite(busDev, LED0_OFF_H + (servoIndex * 4), off>>8);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
Writing new state every cycle for each servo is extremely time consuming
|
||||
and does not makes sense.
|
||||
Trying to sync 5 servos every 2000us extends looptime
|
||||
to 3500us. Very, very bad...
|
||||
Instead of that, write desired values to temporary
|
||||
table and write it to PCA9685 only when there a need.
|
||||
Also, because of resultion of PCA9685 internal counter of about 5us, do not write
|
||||
small changes, since thwy will only clog the bandwidch and will not
|
||||
be represented on output
|
||||
PWM Driver runs at 200Hz, every cycle every 4th servo output is updated:
|
||||
cycle 0: servo 0, 4, 8, 12
|
||||
cycle 1: servo 1, 5, 9, 13
|
||||
cycle 2: servo 2, 6, 10, 14
|
||||
cycle 3: servo3, 7, 11, 15
|
||||
*/
|
||||
void pca9685sync(uint8_t cycleIndex) {
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < PCA9685_SERVO_COUNT; i++) {
|
||||
if (cycleIndex == i % 4 && ABS(temporaryOutputState[i] - currentOutputState[i]) > PCA9685_SYNC_THRESHOLD) {
|
||||
pca9685setPWMOff(i, temporaryOutputState[i]);
|
||||
currentOutputState[i] = temporaryOutputState[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void pca9685setServoPulse(uint8_t servoIndex, uint16_t pulse) {
|
||||
|
||||
static double pulselength = 0;
|
||||
|
||||
if (pulselength == 0) {
|
||||
pulselength = 1000000; // 1,000,000 us per second
|
||||
pulselength /= PCA9685_SERVO_FREQUENCY;
|
||||
pulselength /= 4096; // 12 bits of resolution
|
||||
}
|
||||
pulse /= pulselength;
|
||||
|
||||
temporaryOutputState[servoIndex] = pulse;
|
||||
}
|
||||
|
||||
void pca9685setPWMFreq(uint16_t freq) {
|
||||
|
||||
uint32_t prescaleval = 25000000;
|
||||
prescaleval /= 4096;
|
||||
prescaleval /= freq;
|
||||
prescaleval -= 1;
|
||||
|
||||
busWrite(busDev, PCA9685_MODE1, 16);
|
||||
delay(1);
|
||||
busWrite(busDev, PCA9685_PRESCALE, (uint8_t) prescaleval);
|
||||
delay(1);
|
||||
busWrite(busDev, PCA9685_MODE1, 128);
|
||||
}
|
||||
|
||||
static bool deviceDetect(busDevice_t * busDev)
|
||||
{
|
||||
for (int retry = 0; retry < 5; retry++) {
|
||||
uint8_t sig;
|
||||
|
||||
delay(150);
|
||||
|
||||
bool ack = busRead(busDev, PCA9685_MODE1, &sig);
|
||||
if (ack) {
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool pca9685Initialize(void)
|
||||
{
|
||||
busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_PCA9685, 0, 0);
|
||||
if (busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceDetect(busDev)) {
|
||||
busDeviceDeInit(busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
/* Reset device */
|
||||
busWrite(busDev, PCA9685_MODE1, 0x00);
|
||||
|
||||
/* Set refresh rate */
|
||||
pca9685setPWMFreq(PCA9685_SERVO_FREQUENCY);
|
||||
|
||||
delay(1);
|
||||
|
||||
for (uint8_t i = 0; i < PCA9685_SERVO_COUNT; i++) {
|
||||
pca9685setPWMOn(i, 0);
|
||||
pca9685setPWMOff(i, 1500);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,6 +0,0 @@
|
|||
bool pca9685Initialize(void);
|
||||
void pca9685setPWMOn(uint8_t servoIndex, uint16_t on);
|
||||
void pca9685setPWMOff(uint8_t servoIndex, uint16_t off);
|
||||
void pca9685setPWMFreq(uint16_t freq);
|
||||
void pca9685setServoPulse(uint8_t servoIndex, uint16_t pulse);
|
||||
void pca9685sync(uint8_t cycleIndex);
|
|
@ -3,11 +3,10 @@
|
|||
|
||||
#ifdef USE_LIGHTS
|
||||
|
||||
#if (!defined(LIGHTS_USE_PCA9685_OUTPUT)) && (!defined(LIGHTS_OUTPUT_MODE))
|
||||
#ifndef LIGHTS_OUTPUT_MODE
|
||||
#define LIGHTS_OUTPUT_MODE IOCFG_OUT_PP
|
||||
#endif
|
||||
|
||||
|
||||
static IO_t lightsIO = DEFIO_IO(NONE);
|
||||
|
||||
bool lightsHardwareInit(void)
|
||||
|
|
|
@ -48,7 +48,6 @@ typedef enum {
|
|||
|
||||
typedef enum {
|
||||
SERVO_TYPE_PWM = 0,
|
||||
SERVO_TYPE_SERVO_DRIVER,
|
||||
SERVO_TYPE_SBUS,
|
||||
SERVO_TYPE_SBUS_PWM
|
||||
} servoProtocolType_e;
|
||||
|
|
|
@ -34,9 +34,6 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
|
||||
#include "io/pwmdriver_i2c.h"
|
||||
#include "io/servo_sbus.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
|
||||
|
@ -535,16 +532,6 @@ static void sbusPwmWriteStandard(uint8_t index, uint16_t value)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
static void pwmServoWriteExternalDriver(uint8_t index, uint16_t value)
|
||||
{
|
||||
// If PCA9685 is not detected, we do not want to write servo output anywhere
|
||||
if (STATE(PWM_DRIVER_AVAILABLE)) {
|
||||
pwmDriverSetPulse(index, value);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void pwmServoPreconfigure(void)
|
||||
{
|
||||
// Protocol-specific configuration
|
||||
|
@ -554,13 +541,6 @@ void pwmServoPreconfigure(void)
|
|||
servoWritePtr = pwmServoWriteStandard;
|
||||
break;
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
case SERVO_TYPE_SERVO_DRIVER:
|
||||
pwmDriverInitialize();
|
||||
servoWritePtr = pwmServoWriteExternalDriver;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVO_SBUS
|
||||
case SERVO_TYPE_SBUS:
|
||||
sbusServoInitialize();
|
||||
|
|
|
@ -217,12 +217,6 @@ void validateAndFixConfig(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifndef USE_PWM_SERVO_DRIVER
|
||||
if (servoConfig()->servo_protocol == SERVO_TYPE_SERVO_DRIVER) {
|
||||
servoConfigMutable()->servo_protocol = SERVO_TYPE_PWM;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef USE_SERVO_SBUS
|
||||
if (servoConfig()->servo_protocol == SERVO_TYPE_SBUS || servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM) {
|
||||
servoConfigMutable()->servo_protocol = SERVO_TYPE_PWM;
|
||||
|
|
|
@ -53,7 +53,6 @@
|
|||
#include "drivers/exti.h"
|
||||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
#include "drivers/flash.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/nvic.h"
|
||||
|
@ -75,7 +74,6 @@
|
|||
#include "drivers/uart_inverter.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#ifdef USE_USB_MSC
|
||||
#include "drivers/usb_msc.h"
|
||||
|
@ -114,7 +112,6 @@
|
|||
#include "io/flashfs.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/pwmdriver_i2c.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/osd_dji_hd.h"
|
||||
#include "io/rcdevice_cam.h"
|
||||
|
|
|
@ -61,7 +61,6 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/pwmdriver_i2c.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/rcdevice_cam.h"
|
||||
#include "io/smartport_master.h"
|
||||
|
@ -294,9 +293,6 @@ void taskSyncServoDriver(timeUs_t currentTimeUs)
|
|||
sbusServoSendUpdate();
|
||||
#endif
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
pwmDriverSync();
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_OSD
|
||||
|
@ -368,8 +364,8 @@ void fcTasksInit(void)
|
|||
#ifdef STACK_CHECK
|
||||
setTaskEnabled(TASK_STACK_CHECK, true);
|
||||
#endif
|
||||
#if defined(USE_PWM_SERVO_DRIVER) || defined(USE_SERVO_SBUS)
|
||||
setTaskEnabled(TASK_PWMDRIVER, (servoConfig()->servo_protocol == SERVO_TYPE_SERVO_DRIVER) || (servoConfig()->servo_protocol == SERVO_TYPE_SBUS) || (servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM));
|
||||
#if defined(USE_SERVO_SBUS)
|
||||
setTaskEnabled(TASK_PWMDRIVER, (servoConfig()->servo_protocol == SERVO_TYPE_SBUS) || (servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM));
|
||||
#endif
|
||||
#ifdef USE_CMS
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
|
@ -559,7 +555,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
},
|
||||
#endif
|
||||
|
||||
#if defined(USE_PWM_SERVO_DRIVER) || defined(USE_SERVO_SBUS)
|
||||
#if defined(USE_SERVO_SBUS)
|
||||
[TASK_PWMDRIVER] = {
|
||||
.taskName = "SERVOS",
|
||||
.taskFunc = taskSyncServoDriver,
|
||||
|
|
|
@ -121,7 +121,6 @@ typedef enum {
|
|||
NAV_MOTOR_STOP_OR_IDLE = (1 << 7), // navigation requests MOTOR_STOP or motor idle regardless of throttle stick, will only activate if MOTOR_STOP feature is available
|
||||
COMPASS_CALIBRATED = (1 << 8),
|
||||
ACCELEROMETER_CALIBRATED = (1 << 9),
|
||||
PWM_DRIVER_AVAILABLE = (1 << 10),
|
||||
NAV_CRUISE_BRAKING = (1 << 11),
|
||||
NAV_CRUISE_BRAKING_BOOST = (1 << 12),
|
||||
NAV_CRUISE_BRAKING_LOCKED = (1 << 13),
|
||||
|
|
|
@ -37,7 +37,7 @@ tables:
|
|||
- name: motor_pwm_protocol
|
||||
values: ["STANDARD", "ONESHOT125", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600"]
|
||||
- name: servo_protocol
|
||||
values: ["PWM", "SERVO_DRIVER", "SBUS", "SBUS_PWM"]
|
||||
values: ["PWM", "SBUS", "SBUS_PWM"]
|
||||
- name: failsafe_procedure
|
||||
values: ["LAND", "DROP", "RTH", "NONE"]
|
||||
- name: current_sensor
|
||||
|
@ -1288,7 +1288,7 @@ groups:
|
|||
headers: ["flight/servos.h"]
|
||||
members:
|
||||
- name: servo_protocol
|
||||
description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port)"
|
||||
description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SBUS` (S.Bus protocol output via a configured serial port)"
|
||||
default_value: "PWM"
|
||||
field: servo_protocol
|
||||
table: servo_protocol
|
||||
|
|
|
@ -58,7 +58,7 @@
|
|||
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 3);
|
||||
|
||||
PG_RESET_TEMPLATE(servoConfig_t, servoConfig,
|
||||
.servoCenterPulse = SETTING_SERVO_CENTER_PULSE_DEFAULT,
|
||||
|
|
|
@ -1,70 +0,0 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "drivers/io_pca9685.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
|
||||
#define PWM_DRIVER_IMPLEMENTATION_COUNT 1
|
||||
#define PWM_DRIVER_MAX_CYCLE 4
|
||||
|
||||
static bool driverEnabled = false;
|
||||
static uint8_t driverImplementationIndex = 0;
|
||||
|
||||
typedef struct {
|
||||
bool (*initFunction)(void);
|
||||
void (*writeFunction)(uint8_t servoIndex, uint16_t off);
|
||||
void (*setFrequencyFunction)(uint16_t freq);
|
||||
void (*syncFunction)(uint8_t cycleIndex);
|
||||
} pwmDriverDriver_t;
|
||||
|
||||
pwmDriverDriver_t pwmDrivers[PWM_DRIVER_IMPLEMENTATION_COUNT] = {
|
||||
[0] = {
|
||||
.initFunction = pca9685Initialize,
|
||||
.writeFunction = pca9685setServoPulse,
|
||||
.setFrequencyFunction = pca9685setPWMFreq,
|
||||
.syncFunction = pca9685sync
|
||||
}
|
||||
};
|
||||
|
||||
bool isPwmDriverEnabled(void) {
|
||||
return driverEnabled;
|
||||
}
|
||||
|
||||
void pwmDriverSetPulse(uint8_t servoIndex, uint16_t length) {
|
||||
(pwmDrivers[driverImplementationIndex].writeFunction)(servoIndex, length);
|
||||
}
|
||||
|
||||
void pwmDriverInitialize(void) {
|
||||
driverEnabled = (pwmDrivers[driverImplementationIndex].initFunction)();
|
||||
|
||||
if (driverEnabled) {
|
||||
ENABLE_STATE(PWM_DRIVER_AVAILABLE);
|
||||
} else {
|
||||
DISABLE_STATE(PWM_DRIVER_AVAILABLE);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void pwmDriverSync(void) {
|
||||
if (!STATE(PWM_DRIVER_AVAILABLE)) {
|
||||
return;
|
||||
}
|
||||
|
||||
static uint8_t cycle = 0;
|
||||
|
||||
(pwmDrivers[driverImplementationIndex].syncFunction)(cycle);
|
||||
|
||||
cycle++;
|
||||
if (cycle == PWM_DRIVER_MAX_CYCLE) {
|
||||
cycle = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,4 +0,0 @@
|
|||
|
||||
void pwmDriverInitialize(void);
|
||||
void pwmDriverSync(void);
|
||||
void pwmDriverSetPulse(uint8_t servoIndex, uint16_t length);
|
|
@ -87,7 +87,7 @@ typedef enum {
|
|||
#ifdef USE_LED_STRIP
|
||||
TASK_LEDSTRIP,
|
||||
#endif
|
||||
#if defined(USE_PWM_SERVO_DRIVER) || defined(USE_SERVO_SBUS)
|
||||
#if defined(USE_SERVO_SBUS)
|
||||
TASK_PWMDRIVER,
|
||||
#endif
|
||||
#ifdef STACK_CHECK
|
||||
|
|
|
@ -102,7 +102,6 @@
|
|||
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define PCA9685_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define BNO055_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
|
|
|
@ -144,7 +144,5 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
|
@ -131,5 +131,3 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
|
@ -127,5 +127,3 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -168,5 +168,3 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -135,5 +135,3 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -161,6 +161,5 @@
|
|||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -165,6 +165,5 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -171,7 +171,5 @@
|
|||
|
||||
#define MAX_PWM_OUTPUT_PORTS 4
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
|
@ -124,5 +124,4 @@
|
|||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
|
@ -148,5 +148,3 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -130,5 +130,4 @@
|
|||
#define TARGET_IO_PORTD 0xFFFF
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
|
@ -228,9 +228,7 @@
|
|||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#if defined(OMNIBUSF4V6)
|
||||
#define PCA9685_I2C_BUS BUS_I2C1
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
#else
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
||||
#endif
|
||||
|
|
|
@ -179,5 +179,3 @@
|
|||
#define USE_ESC_SENSOR
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 6
|
||||
|
||||
#define PCA9685_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
|
|
@ -78,7 +78,6 @@
|
|||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C1
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** OSD *****************************
|
||||
|
|
|
@ -106,5 +106,3 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
|
@ -201,5 +201,3 @@
|
|||
#define USE_ESC_SENSOR
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 6
|
||||
|
||||
#define PCA9685_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
|
|
@ -73,7 +73,6 @@
|
|||
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
||||
|
||||
|
||||
|
|
|
@ -177,5 +177,3 @@
|
|||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 9
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -107,7 +107,6 @@
|
|||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
#define PCA9685_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
|
|
|
@ -120,5 +120,4 @@
|
|||
// !!TODO - check the following line is correct
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
|
@ -281,5 +281,3 @@
|
|||
#ifdef OMNIBUSF4PRO
|
||||
#define CURRENT_METER_SCALE 265
|
||||
#endif
|
||||
|
||||
#define PCA9685_I2C_BUS I2C_EXT_BUS
|
||||
|
|
|
@ -196,5 +196,3 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -110,5 +110,3 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -144,5 +144,3 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -135,7 +135,6 @@
|
|||
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define PCA9685_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
|
|
|
@ -105,5 +105,3 @@
|
|||
#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
|
@ -133,5 +133,3 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -156,5 +156,3 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -220,8 +220,6 @@
|
|||
|
||||
#define USE_VTX_FFPV
|
||||
#define USE_PITOT_VIRTUAL
|
||||
#define USE_PWM_DRIVER_PCA9685
|
||||
#define USE_PWM_SERVO_DRIVER
|
||||
|
||||
#define USE_SERIALRX_SUMD
|
||||
#define USE_SERIALRX_SUMH
|
||||
|
|
|
@ -388,15 +388,6 @@
|
|||
BUSDEV_REGISTER_I2C(busdev_ug2864, DEVHW_UG2864, UG2864_I2C_BUS, 0x3C, NONE, DEVFLAGS_NONE, 0);
|
||||
#endif
|
||||
|
||||
#if defined(USE_PWM_SERVO_DRIVER)
|
||||
#if defined(USE_PWM_DRIVER_PCA9685) && defined(USE_I2C)
|
||||
#if !defined(PCA9685_I2C_BUS)
|
||||
#define PCA9685_I2C_BUS BUS_I2C1
|
||||
#endif
|
||||
BUSDEV_REGISTER_I2C(busdev_pca9685, DEVHW_PCA9685, PCA9685_I2C_BUS, 0x40, NONE, DEVFLAGS_NONE, 0);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_IRLOCK) && defined(USE_I2C)
|
||||
#if !defined(IRLOCK_I2C_BUS) && defined(EXTERNAL_I2C_BUS)
|
||||
#define IRLOCK_I2C_BUS EXTERNAL_I2C_BUS
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue