1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

Merge branch 'master' into update_compiler_10_2_1

This commit is contained in:
Jonathan Hudson 2021-08-06 18:19:59 +01:00
commit b5640ce62e
35 changed files with 315 additions and 260 deletions

View file

@ -14,8 +14,6 @@ Current support of rangefinders in INAV is very limited. They are used only to:
Following rangefinders are supported:
* HC-SR04 - ***DO NOT USE*** HC-SR04 while most popular is not suited to use in noise reach environments (like multirotors). It is proven that this sonar rangefinder start to report random values already at 1.5m above solid concrete surface. Reported altitude is valid up to only 75cm above concrete. ***DO NOT USE***
* US-100 in trigger-echo mode - Can be used as direct replacement of _HC-SR04_ when `rangefinder_hardware` is set to _HCSR04_. Useful up to 2m over concrete and correctly reporting _out of range_ when out of range
* SRF10 - experimental
* INAV_I2C - is a simple [DIY rangefinder interface with Arduino Pro Mini 3.3V](https://github.com/iNavFlight/inav-rangefinder). Can be used to connect when flight controller has no Trigger-Echo ports.
* VL53L0X - simple laser rangefinder usable up to 75cm
@ -25,9 +23,8 @@ Following rangefinders are supported:
## Connections
Target dependent in case of Trigger/Echo solutions like `HC-SR04` and `US-100`.
I2C solutions like `VL53L0X` or `INAV_I2C` can be connected to I2C port and used as any other I2C device.
#### Constraints
Target dependent in case of Trigger/Echo solutions like `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.
iNav does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`.

View file

@ -754,11 +754,11 @@ Cutoff frequency for stage 2 D-term low pass filter
### dterm_lpf2_type
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation.
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`.
| Default | Min | Max |
| --- | --- | --- |
| BIQUAD | | |
| PT1 | | |
---
@ -768,17 +768,17 @@ Dterm low pass filter cutoff frequency. Default setting is very conservative and
| Default | Min | Max |
| --- | --- | --- |
| 40 | 0 | 500 |
| 110 | 0 | 500 |
---
### dterm_lpf_type
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation.
Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`.
| Default | Min | Max |
| --- | --- | --- |
| BIQUAD | | |
| PT2 | | |
---

View file

@ -232,8 +232,6 @@ main_sources(COMMON_SRC
drivers/pinio.c
drivers/pinio.h
drivers/rangefinder/rangefinder_hcsr04_i2c.c
drivers/rangefinder/rangefinder_hcsr04_i2c.h
drivers/rangefinder/rangefinder_srf10.c
drivers/rangefinder/rangefinder_srf10.h
drivers/rangefinder/rangefinder_vl53l0x.c

View file

@ -381,4 +381,37 @@ FAST_CODE float alphaBetaGammaFilterApply(alphaBetaGammaFilter_t *filter, float
return filter->xk;
}
#endif
#endif
FUNCTION_COMPILE_FOR_SIZE
void initFilter(const uint8_t filterType, filter_t *filter, const float cutoffFrequency, const uint32_t refreshRate) {
const float dT = refreshRate * 1e-6f;
if (cutoffFrequency) {
if (filterType == FILTER_PT1) {
pt1FilterInit(&filter->pt1, cutoffFrequency, dT);
} if (filterType == FILTER_PT2) {
pt2FilterInit(&filter->pt2, pt2FilterGain(cutoffFrequency, dT));
} if (filterType == FILTER_PT3) {
pt3FilterInit(&filter->pt3, pt3FilterGain(cutoffFrequency, dT));
} else {
biquadFilterInitLPF(&filter->biquad, cutoffFrequency, refreshRate);
}
}
}
FUNCTION_COMPILE_FOR_SIZE
void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyFnPtr *applyFn) {
*applyFn = nullFilterApply;
if (cutoffFrequency) {
if (filterType == FILTER_PT1) {
*applyFn = (filterApplyFnPtr) pt1FilterApply;
} if (filterType == FILTER_PT2) {
*applyFn = (filterApplyFnPtr) pt2FilterApply;
} if (filterType == FILTER_PT3) {
*applyFn = (filterApplyFnPtr) pt3FilterApply;
} else {
*applyFn = (filterApplyFnPtr) biquadFilterApply;
}
}
}

View file

@ -47,12 +47,16 @@ typedef struct biquadFilter_s {
typedef union {
biquadFilter_t biquad;
pt1Filter_t pt1;
pt1Filter_t pt1;
pt2Filter_t pt2;
pt3Filter_t pt3;
} filter_t;
typedef enum {
FILTER_PT1 = 0,
FILTER_BIQUAD
FILTER_BIQUAD,
FILTER_PT2,
FILTER_PT3
} filterType_e;
typedef enum {
@ -127,4 +131,7 @@ float filterGetNotchQ(float centerFrequencyHz, float cutoffFrequencyHz);
void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
void alphaBetaGammaFilterInit(alphaBetaGammaFilter_t *filter, float alpha, float boostGain, float halfLife, float dT);
float alphaBetaGammaFilterApply(alphaBetaGammaFilter_t *filter, float input);
float alphaBetaGammaFilterApply(alphaBetaGammaFilter_t *filter, float input);
void initFilter(uint8_t filterType, filter_t *filter, float cutoffFrequency, uint32_t refreshRate);
void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyFnPtr *applyFn);

View file

@ -140,7 +140,6 @@ typedef enum {
/* Rangefinder modules */
DEVHW_SRF10,
DEVHW_HCSR04_I2C, // DIY-style adapter
DEVHW_VL53L0X,
DEVHW_VL53L1X,
DEVHW_US42,

View file

@ -107,7 +107,6 @@ bool vcm5883Detect(magDev_t * mag)
}
if (!deviceDetect(mag)) {
DEBUG_SET(DEBUG_ALWAYS, 0, 7);
busDeviceDeInit(mag->busDev);
return false;
}

View file

@ -1,125 +0,0 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV 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.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#if defined(USE_RANGEFINDER) && defined(USE_RANGEFINDER_HCSR04_I2C)
#include "build/build_config.h"
#include "drivers/time.h"
#include "drivers/bus_i2c.h"
#include "drivers/rangefinder/rangefinder.h"
#include "drivers/rangefinder/rangefinder_hcsr04_i2c.h"
#include "build/debug.h"
#define HCSR04_I2C_MAX_RANGE_CM 400
#define HCSR04_I2C_DETECTION_CONE_DECIDEGREES 300
#define HCSR04_I2C_DETECTION_CONE_EXTENDED_DECIDEGREES 450
#define HCSR04_I2C_Address 0x14
#define HCSR04_I2C_REGISTRY_STATUS 0x00
#define HCSR04_I2C_REGISTRY_DISTANCE_HIGH 0x01
#define HCSR04_I2C_REGISTRY_DISTANCE_LOW 0x02
volatile int32_t hcsr04i2cMeasurementCm = RANGEFINDER_OUT_OF_RANGE;
static bool isHcsr04i2cResponding = false;
static void hcsr04i2cInit(rangefinderDev_t *rangefinder)
{
UNUSED(rangefinder);
}
void hcsr04i2cUpdate(rangefinderDev_t *rangefinder)
{
uint8_t response[3];
isHcsr04i2cResponding = busReadBuf(rangefinder->busDev, HCSR04_I2C_REGISTRY_STATUS, response, 3);
if (!isHcsr04i2cResponding) {
hcsr04i2cMeasurementCm = RANGEFINDER_HARDWARE_FAILURE;
return;
}
if (response[HCSR04_I2C_REGISTRY_STATUS] == 0) {
hcsr04i2cMeasurementCm =
(int32_t)((int32_t)response[HCSR04_I2C_REGISTRY_DISTANCE_HIGH] << 8) +
response[HCSR04_I2C_REGISTRY_DISTANCE_LOW];
} else {
/*
* Rangefinder is reporting out-of-range situation
*/
hcsr04i2cMeasurementCm = RANGEFINDER_OUT_OF_RANGE;
}
}
/**
* Get the distance that was measured by the last pulse, in centimeters.
*/
int32_t hcsr04i2cGetDistance(rangefinderDev_t *rangefinder)
{
UNUSED(rangefinder);
return hcsr04i2cMeasurementCm;
}
static bool deviceDetect(busDevice_t * busDev)
{
for (int retry = 0; retry < 5; retry++) {
uint8_t inquiryResult;
delay(150);
bool ack = busRead(busDev, HCSR04_I2C_REGISTRY_STATUS, &inquiryResult);
if (ack) {
return true;
}
};
return false;
}
bool hcsr04i2c0Detect(rangefinderDev_t *rangefinder)
{
rangefinder->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_HCSR04_I2C, 0, OWNER_RANGEFINDER);
if (rangefinder->busDev == NULL) {
return false;
}
if (!deviceDetect(rangefinder->busDev)) {
busDeviceDeInit(rangefinder->busDev);
return false;
}
rangefinder->delayMs = RANGEFINDER_HCSR04_i2C_TASK_PERIOD_MS;
rangefinder->maxRangeCm = HCSR04_I2C_MAX_RANGE_CM;
rangefinder->detectionConeDeciDegrees = HCSR04_I2C_DETECTION_CONE_DECIDEGREES;
rangefinder->detectionConeExtendedDeciDegrees = HCSR04_I2C_DETECTION_CONE_EXTENDED_DECIDEGREES;
rangefinder->init = &hcsr04i2cInit;
rangefinder->update = &hcsr04i2cUpdate;
rangefinder->read = &hcsr04i2cGetDistance;
return true;
}
#endif

View file

@ -1,22 +0,0 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV 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.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define RANGEFINDER_HCSR04_i2C_TASK_PERIOD_MS 100
bool hcsr04i2c0Detect(rangefinderDev_t *dev);

View file

@ -7,7 +7,7 @@ tables:
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "FAKE"]
enum: accelerationSensor_e
- name: rangefinder_hardware
values: ["NONE", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"]
values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"]
enum: rangefinderType_e
- name: secondary_imu_hardware
values: ["NONE", "BNO055", "BNO055_SERIAL"]
@ -129,6 +129,8 @@ tables:
enum: vtxLowerPowerDisarm_e
- name: filter_type
values: ["PT1", "BIQUAD"]
- name: filter_type_full
values: ["PT1", "BIQUAD", "PT2", "PT3"]
- name: log_level
values: ["ERROR", "WARNING", "INFO", "VERBOSE", "DEBUG"]
- name: iterm_relax
@ -1884,24 +1886,24 @@ groups:
max: 900
- name: dterm_lpf_hz
description: "Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value"
default_value: 40
default_value: 110
min: 0
max: 500
- name: dterm_lpf_type
description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
default_value: "BIQUAD"
description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`."
default_value: "PT2"
field: dterm_lpf_type
table: filter_type
table: filter_type_full
- name: dterm_lpf2_hz
description: "Cutoff frequency for stage 2 D-term low pass filter"
default_value: 0
min: 0
max: 500
- name: dterm_lpf2_type
description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
default_value: "BIQUAD"
description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`."
default_value: "PT1"
field: dterm_lpf2_type
table: filter_type
table: filter_type_full
- name: yaw_lpf_hz
description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)"
default_value: 0

View file

@ -309,6 +309,7 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
#endif
);
FUNCTION_COMPILE_FOR_SIZE
bool pidInitFilters(void)
{
const uint32_t refreshRate = getLooptime();
@ -317,26 +318,9 @@ bool pidInitFilters(void)
return false;
}
// Init other filters
if (pidProfile()->dterm_lpf_hz) {
for (int axis = 0; axis < 3; ++ axis) {
if (pidProfile()->dterm_lpf_type == FILTER_PT1) {
pt1FilterInit(&pidState[axis].dtermLpfState.pt1, pidProfile()->dterm_lpf_hz, refreshRate * 1e-6f);
} else {
biquadFilterInitLPF(&pidState[axis].dtermLpfState.biquad, pidProfile()->dterm_lpf_hz, refreshRate);
}
}
}
// Init other filters
if (pidProfile()->dterm_lpf2_hz) {
for (int axis = 0; axis < 3; ++ axis) {
if (pidProfile()->dterm_lpf2_type == FILTER_PT1) {
pt1FilterInit(&pidState[axis].dtermLpf2State.pt1, pidProfile()->dterm_lpf2_hz, refreshRate * 1e-6f);
} else {
biquadFilterInitLPF(&pidState[axis].dtermLpf2State.biquad, pidProfile()->dterm_lpf2_hz, refreshRate);
}
}
for (int axis = 0; axis < 3; ++ axis) {
initFilter(pidProfile()->dterm_lpf_type, &pidState[axis].dtermLpfState, pidProfile()->dterm_lpf_hz, refreshRate);
initFilter(pidProfile()->dterm_lpf2_type, &pidState[axis].dtermLpf2State, pidProfile()->dterm_lpf2_hz, refreshRate);
}
for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
@ -713,8 +697,6 @@ static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) {
dBoost = pt1FilterApply4(&pidState->dBoostLpf, dBoost, D_BOOST_LPF_HZ, dT);
dBoost = constrainf(dBoost, dBoostMin, dBoostMax);
DEBUG_SET(DEBUG_ALWAYS, pidState->axis, dBoost * 100);
return dBoost;
}
#else
@ -733,7 +715,7 @@ static float dTermProcess(pidState_t *pidState, float dT) {
newDTerm = 0;
} else {
float delta = pidState->previousRateGyro - pidState->gyroRate;
delta = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, delta);
delta = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, delta);
@ -1230,23 +1212,8 @@ void pidInit(void)
usedPidControllerType = pidProfile()->pidControllerType;
}
dTermLpfFilterApplyFn = nullFilterApply;
if (pidProfile()->dterm_lpf_hz) {
if (pidProfile()->dterm_lpf_type == FILTER_PT1) {
dTermLpfFilterApplyFn = (filterApplyFnPtr) pt1FilterApply;
} else {
dTermLpfFilterApplyFn = (filterApplyFnPtr) biquadFilterApply;
}
}
dTermLpf2FilterApplyFn = nullFilterApply;
if (pidProfile()->dterm_lpf2_hz) {
if (pidProfile()->dterm_lpf2_type == FILTER_PT1) {
dTermLpf2FilterApplyFn = (filterApplyFnPtr) pt1FilterApply;
} else {
dTermLpf2FilterApplyFn = (filterApplyFnPtr) biquadFilterApply;
}
}
assignFilterApplyFn(pidProfile()->dterm_lpf_type, pidProfile()->dterm_lpf_hz, &dTermLpfFilterApplyFn);
assignFilterApplyFn(pidProfile()->dterm_lpf2_type, pidProfile()->dterm_lpf2_hz, &dTermLpf2FilterApplyFn);
if (usedPidControllerType == PID_TYPE_PIFF) {
pidControllerApplyFn = pidApplyFixedWingRateController;

View file

@ -37,7 +37,6 @@
#include "drivers/time.h"
#include "drivers/rangefinder/rangefinder.h"
#include "drivers/rangefinder/rangefinder_srf10.h"
#include "drivers/rangefinder/rangefinder_hcsr04_i2c.h"
#include "drivers/rangefinder/rangefinder_vl53l0x.h"
#include "drivers/rangefinder/rangefinder_vl53l1x.h"
#include "drivers/rangefinder/rangefinder_virtual.h"
@ -64,7 +63,7 @@ rangefinder_t rangefinder;
#define RANGEFINDER_DYNAMIC_FACTOR 75
#ifdef USE_RANGEFINDER
PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 2);
PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 3);
PG_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig,
.rangefinder_hardware = SETTING_RANGEFINDER_HARDWARE_DEFAULT,
@ -89,15 +88,6 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar
#endif
break;
case RANGEFINDER_HCSR04I2C:
#ifdef USE_RANGEFINDER_HCSR04_I2C
if (hcsr04i2c0Detect(dev)) {
rangefinderHardware = RANGEFINDER_HCSR04I2C;
rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_HCSR04_i2C_TASK_PERIOD_MS));
}
#endif
break;
case RANGEFINDER_VL53L0X:
#if defined(USE_RANGEFINDER_VL53L0X)
if (vl53l0xDetect(dev)) {

View file

@ -24,13 +24,12 @@
typedef enum {
RANGEFINDER_NONE = 0,
RANGEFINDER_SRF10 = 1,
RANGEFINDER_HCSR04I2C = 2,
RANGEFINDER_VL53L0X = 3,
RANGEFINDER_MSP = 4,
RANGEFINDER_BENEWAKE = 5,
RANGEFINDER_VL53L1X = 6,
RANGEFINDER_US42 = 7,
RANGEFINDER_TOF10102I2C = 8,
RANGEFINDER_VL53L0X = 2,
RANGEFINDER_MSP = 3,
RANGEFINDER_BENEWAKE = 4,
RANGEFINDER_VL53L1X = 5,
RANGEFINDER_US42 = 6,
RANGEFINDER_TOF10102I2C = 7,
} rangefinderType_e;
typedef struct rangefinderConfig_s {

View file

@ -110,7 +110,6 @@
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define USE_RANGEFINDER_HCSR04_I2C
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1

View file

@ -65,7 +65,6 @@
#define PITOT_I2C_BUS BUS_I2C2
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define USE_VCP

View file

@ -141,7 +141,6 @@
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define USE_RANGEFINDER_HCSR04_I2C
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1

View file

@ -98,7 +98,6 @@
#define BNO055_I2C_BUS BUS_I2C1
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS

View file

@ -123,7 +123,6 @@
#else
#define RANGEFINDER_I2C_BUS BUS_I2C2
#endif
#define USE_RANGEFINDER_HCSR04_I2C
#define USE_VCP
#define VBUS_SENSING_PIN PC5

View file

@ -137,7 +137,6 @@
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS

View file

@ -115,7 +115,6 @@
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C1
// *************** ADC *****************************

View file

@ -165,7 +165,6 @@
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS

View file

@ -68,7 +68,6 @@
#define USE_MAG_LIS3MDL
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define PITOT_I2C_BUS BUS_I2C2

View file

@ -71,7 +71,6 @@
#define USE_MAG_LIS3MDL
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define USE_RANGEFINDER_US42
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define PITOT_I2C_BUS BUS_I2C2

View file

@ -121,7 +121,6 @@
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C1
// *************** ADC *****************************

View file

@ -159,7 +159,6 @@
#define BNO055_I2C_BUS BUS_I2C2
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C2
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO)

View file

@ -132,7 +132,6 @@
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS

View file

@ -0,0 +1 @@
target_stm32f722xe(SPEEDYBEEF7V2)

View file

@ -0,0 +1,35 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
#include "io/serial.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
}

View file

@ -0,0 +1,42 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/bus.h"
const timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S1
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2
DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_LED, 0, 0), // LED
DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // Camera Control
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,163 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "SB72"
#define USBD_PRODUCT_STRING "SpeedyBeeF7V2"
#define USE_TARGET_CONFIG
#define LED0 PC13
// *************** UART *****************************
#define USB_IO
#define USE_VCP
#define VBUS_SENSING_PIN PC15
#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_RX_PIN PB7
#define UART1_TX_PIN PB6
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PC11
#define UART3_TX_PIN PC10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
// *************** Gyro & ACC **********************
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW0_DEG
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_EXTI
#define GYRO_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_BEEPER
#define BEEPER PB2
#define BEEPER_INVERTED
// *************** I2C(Baro & I2C) **************************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11
// Baro
#define USE_BARO
#define USE_BARO_BMP280
#define USE_BARO_DPS310
#define BARO_I2C_BUS BUS_I2C1
// Mag
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_I2C_BUS BUS_I2C2
// *************** Flash **************************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PA14
#define M25P16_SPI_BUS BUS_SPI3
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// *************** OSD *****************************
#define USE_OSD
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// *************** ADC *****************************
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC1
#define ADC_CHANNEL_3_PIN PC3
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_SERIALSHOT
#define SERIALRX_UART SERIAL_PORT_USART1
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define MAX_PWM_OUTPUT_PORTS 4
#define CURRENT_METER_SCALE 102
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PA15
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

View file

@ -96,7 +96,6 @@
#define WS2811_PIN PA8
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT

View file

@ -123,9 +123,6 @@
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define USE_RANGEFINDER_HCSR04
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0
#define RANGEFINDER_HCSR04_ECHO_PIN PB1
#define USE_RANGEFINDER_SRF10
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View file

@ -56,9 +56,6 @@
#define USE_MAG_LIS3MDL
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04
#define RANGEFINDER_HCSR04_ECHO_PIN PB1
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0
#define USB_CABLE_DETECTION

View file

@ -104,7 +104,6 @@
#define USE_RANGEFINDER_BENEWAKE
#define USE_RANGEFINDER_VL53L0X
#define USE_RANGEFINDER_VL53L1X
#define USE_RANGEFINDER_HCSR04_I2C
#define USE_RANGEFINDER_US42
#define USE_RANGEFINDER_TOF10120_I2C

View file

@ -303,15 +303,6 @@
#endif
#endif
#if defined(USE_RANGEFINDER_HCSR04_I2C) && (defined(HCSR04_I2C_BUS) || defined(RANGEFINDER_I2C_BUS))
#if !defined(HCSR04_I2C_BUS)
#define HCSR04_I2C_BUS RANGEFINDER_I2C_BUS
#endif
#if defined(HCSR04_I2C_BUS)
BUSDEV_REGISTER_I2C(busdev_hcsr04, DEVHW_HCSR04_I2C, HCSR04_I2C_BUS, 0x14, NONE, DEVFLAGS_NONE, 0);
#endif
#endif
#if defined(USE_RANGEFINDER_VL53L0X)
#if !defined(VL53L0X_I2C_BUS) && defined(RANGEFINDER_I2C_BUS)
#define VL53L0X_I2C_BUS RANGEFINDER_I2C_BUS