mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-15 20:35:29 +03:00
Sync with master
This commit is contained in:
parent
a2330168b5
commit
ec6c99a5dc
59 changed files with 210 additions and 761 deletions
|
@ -2852,26 +2852,6 @@ When powering up, gyro bias is calculated. If the model is shaking/moving during
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
### motor_accel_time
|
|
||||||
|
|
||||||
Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | 0 | 1000 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### motor_decel_time
|
|
||||||
|
|
||||||
Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]
|
|
||||||
|
|
||||||
| Default | Min | Max |
|
|
||||||
| --- | --- | --- |
|
|
||||||
| 0 | 0 | 1000 |
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
### motor_direction_inverted
|
### motor_direction_inverted
|
||||||
|
|
||||||
Use if you need to inverse yaw motor direction.
|
Use if you need to inverse yaw motor direction.
|
||||||
|
|
|
@ -164,6 +164,8 @@ main_sources(COMMON_SRC
|
||||||
drivers/compass/compass_qmc5883l.h
|
drivers/compass/compass_qmc5883l.h
|
||||||
drivers/compass/compass_rm3100.c
|
drivers/compass/compass_rm3100.c
|
||||||
drivers/compass/compass_rm3100.h
|
drivers/compass/compass_rm3100.h
|
||||||
|
drivers/compass/compass_vcm5883.c
|
||||||
|
drivers/compass/compass_vcm5883.h
|
||||||
drivers/compass/compass_msp.c
|
drivers/compass/compass_msp.c
|
||||||
drivers/compass/compass_msp.h
|
drivers/compass/compass_msp.h
|
||||||
|
|
||||||
|
@ -230,8 +232,6 @@ main_sources(COMMON_SRC
|
||||||
drivers/pinio.c
|
drivers/pinio.c
|
||||||
drivers/pinio.h
|
drivers/pinio.h
|
||||||
|
|
||||||
drivers/rangefinder/rangefinder_hcsr04.c
|
|
||||||
drivers/rangefinder/rangefinder_hcsr04.h
|
|
||||||
drivers/rangefinder/rangefinder_hcsr04_i2c.c
|
drivers/rangefinder/rangefinder_hcsr04_i2c.c
|
||||||
drivers/rangefinder/rangefinder_hcsr04_i2c.h
|
drivers/rangefinder/rangefinder_hcsr04_i2c.h
|
||||||
drivers/rangefinder/rangefinder_srf10.c
|
drivers/rangefinder/rangefinder_srf10.c
|
||||||
|
@ -355,8 +355,6 @@ main_sources(COMMON_SRC
|
||||||
|
|
||||||
io/beeper.c
|
io/beeper.c
|
||||||
io/beeper.h
|
io/beeper.h
|
||||||
io/esc_serialshot.c
|
|
||||||
io/esc_serialshot.h
|
|
||||||
io/servo_sbus.c
|
io/servo_sbus.c
|
||||||
io/servo_sbus.h
|
io/servo_sbus.h
|
||||||
io/frsky_osd.c
|
io/frsky_osd.c
|
||||||
|
|
|
@ -120,6 +120,7 @@ typedef enum {
|
||||||
DEVHW_MAG3110,
|
DEVHW_MAG3110,
|
||||||
DEVHW_LIS3MDL,
|
DEVHW_LIS3MDL,
|
||||||
DEVHW_RM3100,
|
DEVHW_RM3100,
|
||||||
|
DEVHW_VCM5883,
|
||||||
|
|
||||||
/* Temp sensor chips */
|
/* Temp sensor chips */
|
||||||
DEVHW_LM75_0,
|
DEVHW_LM75_0,
|
||||||
|
|
121
src/main/drivers/compass/compass_vcm5883.c
Normal file
121
src/main/drivers/compass/compass_vcm5883.c
Normal file
|
@ -0,0 +1,121 @@
|
||||||
|
/*
|
||||||
|
* This file is part of INAV.
|
||||||
|
*
|
||||||
|
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||||
|
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||||
|
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||||
|
*
|
||||||
|
* Alternatively, the contents of this file may be used under the terms
|
||||||
|
* of the GNU General Public License Version 3, as described below:
|
||||||
|
*
|
||||||
|
* This file is free software: you may copy, redistribute 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.
|
||||||
|
*
|
||||||
|
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_MAG_VCM5883
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "common/axis.h"
|
||||||
|
#include "common/maths.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/time.h"
|
||||||
|
#include "drivers/bus_i2c.h"
|
||||||
|
|
||||||
|
#include "sensors/boardalignment.h"
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
|
#include "drivers/sensor.h"
|
||||||
|
#include "drivers/compass/compass.h"
|
||||||
|
|
||||||
|
#include "drivers/compass/compass_vcm5883.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#define VCM5883_REGISTER_ADDR_CNTL1 0x0B
|
||||||
|
#define VCM5883_REGISTER_ADDR_CNTL2 0x0A
|
||||||
|
#define VCM5883_REGISTER_ADDR_CHIPID 0x0C
|
||||||
|
#define VCM5883_REGISTER_ADDR_OUTPUT_X 0x00
|
||||||
|
#define VCM5883_INITIAL_CONFIG 0b0100
|
||||||
|
|
||||||
|
#define DETECTION_MAX_RETRY_COUNT 5
|
||||||
|
static bool deviceDetect(magDev_t * mag)
|
||||||
|
{
|
||||||
|
for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) {
|
||||||
|
busWrite(mag->busDev, VCM5883_REGISTER_ADDR_CNTL2, 0b01000001);
|
||||||
|
delay(30);
|
||||||
|
|
||||||
|
uint8_t sig = 0;
|
||||||
|
bool ack = busRead(mag->busDev, VCM5883_REGISTER_ADDR_CHIPID, &sig);
|
||||||
|
|
||||||
|
if (ack && sig == 0x82) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool vcm5883Init(magDev_t * mag) {
|
||||||
|
UNUSED(mag);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool vcm5883Read(magDev_t * mag)
|
||||||
|
{
|
||||||
|
uint8_t buf[6];
|
||||||
|
|
||||||
|
// set magData to zero for case of failed read
|
||||||
|
mag->magADCRaw[X] = 0;
|
||||||
|
mag->magADCRaw[Y] = 0;
|
||||||
|
mag->magADCRaw[Z] = 0;
|
||||||
|
|
||||||
|
bool ack = busReadBuf(mag->busDev, VCM5883_REGISTER_ADDR_OUTPUT_X, buf, 6);
|
||||||
|
if (!ack) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
mag->magADCRaw[X] = (int16_t)(buf[1] << 8 | buf[0]);
|
||||||
|
mag->magADCRaw[Y] = (int16_t)(buf[3] << 8 | buf[2]);
|
||||||
|
mag->magADCRaw[Z] = (int16_t)(buf[5] << 8 | buf[4]);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool vcm5883Detect(magDev_t * mag)
|
||||||
|
{
|
||||||
|
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_VCM5883, mag->magSensorToUse, OWNER_COMPASS);
|
||||||
|
if (mag->busDev == NULL) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!deviceDetect(mag)) {
|
||||||
|
DEBUG_SET(DEBUG_ALWAYS, 0, 7);
|
||||||
|
busDeviceDeInit(mag->busDev);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
mag->init = vcm5883Init;
|
||||||
|
mag->read = vcm5883Read;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of INAV Project.
|
* This file is part of INAV.
|
||||||
*
|
*
|
||||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||||
|
@ -24,6 +24,4 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool serialshotInitialize(void);
|
bool vcm5883Detect(magDev_t *mag);
|
||||||
void serialshotUpdateMotor(int index, uint16_t value);
|
|
||||||
void serialshotSendUpdate(void);
|
|
|
@ -5,6 +5,8 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#ifdef USE_PWM_DRIVER_PCA9685
|
||||||
|
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
|
@ -141,3 +143,5 @@ bool pca9685Initialize(void)
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -67,16 +67,13 @@ static const char * pwmInitErrorMsg[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
static const motorProtocolProperties_t motorProtocolProperties[] = {
|
static const motorProtocolProperties_t motorProtocolProperties[] = {
|
||||||
[PWM_TYPE_STANDARD] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
[PWM_TYPE_STANDARD] = { .usesHwTimer = true, .isDSHOT = false },
|
||||||
[PWM_TYPE_ONESHOT125] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
[PWM_TYPE_ONESHOT125] = { .usesHwTimer = true, .isDSHOT = false },
|
||||||
[PWM_TYPE_ONESHOT42] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
[PWM_TYPE_MULTISHOT] = { .usesHwTimer = true, .isDSHOT = false },
|
||||||
[PWM_TYPE_MULTISHOT] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
[PWM_TYPE_BRUSHED] = { .usesHwTimer = true, .isDSHOT = false },
|
||||||
[PWM_TYPE_BRUSHED] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false },
|
[PWM_TYPE_DSHOT150] = { .usesHwTimer = true, .isDSHOT = true },
|
||||||
[PWM_TYPE_DSHOT150] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
[PWM_TYPE_DSHOT300] = { .usesHwTimer = true, .isDSHOT = true },
|
||||||
[PWM_TYPE_DSHOT300] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
[PWM_TYPE_DSHOT600] = { .usesHwTimer = true, .isDSHOT = true },
|
||||||
[PWM_TYPE_DSHOT600] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
|
||||||
[PWM_TYPE_DSHOT1200] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false },
|
|
||||||
[PWM_TYPE_SERIALSHOT] = { .usesHwTimer = false, .isDSHOT = false, .isSerialShot = true },
|
|
||||||
};
|
};
|
||||||
|
|
||||||
pwmInitError_e getPwmInitError(void)
|
pwmInitError_e getPwmInitError(void)
|
||||||
|
@ -199,17 +196,6 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw)
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_RANGEFINDER_HCSR04
|
|
||||||
// HC-SR04 has a dedicated connection to FC and require two pins
|
|
||||||
if (rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) {
|
|
||||||
const rangefinderHardwarePins_t *rangefinderHardwarePins = rangefinderGetHardwarePins();
|
|
||||||
if (rangefinderHardwarePins && (timHw->tag == rangefinderHardwarePins->triggerTag || timHw->tag == rangefinderHardwarePins->echoTag)) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -39,14 +39,11 @@
|
||||||
typedef enum {
|
typedef enum {
|
||||||
PWM_TYPE_STANDARD = 0,
|
PWM_TYPE_STANDARD = 0,
|
||||||
PWM_TYPE_ONESHOT125,
|
PWM_TYPE_ONESHOT125,
|
||||||
PWM_TYPE_ONESHOT42,
|
|
||||||
PWM_TYPE_MULTISHOT,
|
PWM_TYPE_MULTISHOT,
|
||||||
PWM_TYPE_BRUSHED,
|
PWM_TYPE_BRUSHED,
|
||||||
PWM_TYPE_DSHOT150,
|
PWM_TYPE_DSHOT150,
|
||||||
PWM_TYPE_DSHOT300,
|
PWM_TYPE_DSHOT300,
|
||||||
PWM_TYPE_DSHOT600,
|
PWM_TYPE_DSHOT600,
|
||||||
PWM_TYPE_DSHOT1200,
|
|
||||||
PWM_TYPE_SERIALSHOT,
|
|
||||||
} motorPwmProtocolTypes_e;
|
} motorPwmProtocolTypes_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -73,7 +70,6 @@ typedef struct rangefinderIOConfig_s {
|
||||||
typedef struct {
|
typedef struct {
|
||||||
bool usesHwTimer;
|
bool usesHwTimer;
|
||||||
bool isDSHOT;
|
bool isDSHOT;
|
||||||
bool isSerialShot;
|
|
||||||
} motorProtocolProperties_t;
|
} motorProtocolProperties_t;
|
||||||
|
|
||||||
bool pwmMotorAndServoInit(void);
|
bool pwmMotorAndServoInit(void);
|
||||||
|
|
|
@ -37,7 +37,6 @@ FILE_COMPILE_FOR_SPEED
|
||||||
#include "drivers/io_pca9685.h"
|
#include "drivers/io_pca9685.h"
|
||||||
|
|
||||||
#include "io/pwmdriver_i2c.h"
|
#include "io/pwmdriver_i2c.h"
|
||||||
#include "io/esc_serialshot.h"
|
|
||||||
#include "io/servo_sbus.h"
|
#include "io/servo_sbus.h"
|
||||||
#include "sensors/esc_sensor.h"
|
#include "sensors/esc_sensor.h"
|
||||||
|
|
||||||
|
@ -50,7 +49,6 @@ FILE_COMPILE_FOR_SPEED
|
||||||
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_HZ * 20 / 1000000.0f / 1000.0f)
|
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_HZ * 20 / 1000000.0f / 1000.0f)
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
#define MOTOR_DSHOT1200_HZ 24000000
|
|
||||||
#define MOTOR_DSHOT600_HZ 12000000
|
#define MOTOR_DSHOT600_HZ 12000000
|
||||||
#define MOTOR_DSHOT300_HZ 6000000
|
#define MOTOR_DSHOT300_HZ 6000000
|
||||||
#define MOTOR_DSHOT150_HZ 3000000
|
#define MOTOR_DSHOT150_HZ 3000000
|
||||||
|
@ -100,7 +98,7 @@ static pwmWriteFuncPtr motorWritePtr = NULL; // Function to write val
|
||||||
static pwmOutputPort_t * servos[MAX_SERVOS];
|
static pwmOutputPort_t * servos[MAX_SERVOS];
|
||||||
static pwmWriteFuncPtr servoWritePtr = NULL; // Function to write value to motors
|
static pwmWriteFuncPtr servoWritePtr = NULL; // Function to write value to motors
|
||||||
|
|
||||||
#if defined(USE_DSHOT) || defined(USE_SERIALSHOT)
|
#if defined(USE_DSHOT)
|
||||||
static timeUs_t digitalMotorUpdateIntervalUs = 0;
|
static timeUs_t digitalMotorUpdateIntervalUs = 0;
|
||||||
static timeUs_t digitalMotorLastUpdateUs;
|
static timeUs_t digitalMotorLastUpdateUs;
|
||||||
#endif
|
#endif
|
||||||
|
@ -245,8 +243,6 @@ static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, fl
|
||||||
uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType)
|
uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType)
|
||||||
{
|
{
|
||||||
switch (pwmProtocolType) {
|
switch (pwmProtocolType) {
|
||||||
case(PWM_TYPE_DSHOT1200):
|
|
||||||
return MOTOR_DSHOT1200_HZ;
|
|
||||||
case(PWM_TYPE_DSHOT600):
|
case(PWM_TYPE_DSHOT600):
|
||||||
return MOTOR_DSHOT600_HZ;
|
return MOTOR_DSHOT600_HZ;
|
||||||
case(PWM_TYPE_DSHOT300):
|
case(PWM_TYPE_DSHOT300):
|
||||||
|
@ -304,7 +300,7 @@ static uint16_t prepareDshotPacket(const uint16_t value, bool requestTelemetry)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_DSHOT) || defined(USE_SERIALSHOT)
|
#if defined(USE_DSHOT)
|
||||||
static void motorConfigDigitalUpdateInterval(uint16_t motorPwmRateHz)
|
static void motorConfigDigitalUpdateInterval(uint16_t motorPwmRateHz)
|
||||||
{
|
{
|
||||||
digitalMotorUpdateIntervalUs = 1000000 / motorPwmRateHz;
|
digitalMotorUpdateIntervalUs = 1000000 / motorPwmRateHz;
|
||||||
|
@ -325,14 +321,9 @@ bool isMotorProtocolDshot(void)
|
||||||
return getMotorProtocolProperties(initMotorProtocol)->isDSHOT;
|
return getMotorProtocolProperties(initMotorProtocol)->isDSHOT;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isMotorProtocolSerialShot(void)
|
|
||||||
{
|
|
||||||
return getMotorProtocolProperties(initMotorProtocol)->isSerialShot;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool isMotorProtocolDigital(void)
|
bool isMotorProtocolDigital(void)
|
||||||
{
|
{
|
||||||
return isMotorProtocolDshot() || isMotorProtocolSerialShot();
|
return isMotorProtocolDshot();
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmRequestMotorTelemetry(int motorIndex)
|
void pwmRequestMotorTelemetry(int motorIndex)
|
||||||
|
@ -441,16 +432,6 @@ void pwmCompleteMotorUpdate(void) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_SERIALSHOT
|
|
||||||
if (isMotorProtocolSerialShot()) {
|
|
||||||
for (int index = 0; index < motorCount; index++) {
|
|
||||||
serialshotUpdateMotor(index, motors[index].value);
|
|
||||||
}
|
|
||||||
|
|
||||||
serialshotSendUpdate();
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#else // digital motor protocol
|
#else // digital motor protocol
|
||||||
|
@ -481,13 +462,11 @@ void pwmMotorPreconfigure(void)
|
||||||
case PWM_TYPE_STANDARD:
|
case PWM_TYPE_STANDARD:
|
||||||
case PWM_TYPE_BRUSHED:
|
case PWM_TYPE_BRUSHED:
|
||||||
case PWM_TYPE_ONESHOT125:
|
case PWM_TYPE_ONESHOT125:
|
||||||
case PWM_TYPE_ONESHOT42:
|
|
||||||
case PWM_TYPE_MULTISHOT:
|
case PWM_TYPE_MULTISHOT:
|
||||||
motorWritePtr = pwmWriteStandard;
|
motorWritePtr = pwmWriteStandard;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
case PWM_TYPE_DSHOT1200:
|
|
||||||
case PWM_TYPE_DSHOT600:
|
case PWM_TYPE_DSHOT600:
|
||||||
case PWM_TYPE_DSHOT300:
|
case PWM_TYPE_DSHOT300:
|
||||||
case PWM_TYPE_DSHOT150:
|
case PWM_TYPE_DSHOT150:
|
||||||
|
@ -495,15 +474,6 @@ void pwmMotorPreconfigure(void)
|
||||||
motorWritePtr = pwmWriteDigital;
|
motorWritePtr = pwmWriteDigital;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_SERIALSHOT
|
|
||||||
case PWM_TYPE_SERIALSHOT:
|
|
||||||
// Kick off SerialShot driver initalization
|
|
||||||
serialshotInitialize();
|
|
||||||
motorConfigDigitalUpdateInterval(motorConfig()->motorPwmRate);
|
|
||||||
motorWritePtr = pwmWriteDigital;
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -518,16 +488,11 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bo
|
||||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorConfig()->motorPwmRate, enableOutput);
|
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorConfig()->motorPwmRate, enableOutput);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case PWM_TYPE_ONESHOT42:
|
|
||||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 42e-6f, 42e-6f, motorConfig()->motorPwmRate, enableOutput);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case PWM_TYPE_MULTISHOT:
|
case PWM_TYPE_MULTISHOT:
|
||||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorConfig()->motorPwmRate, enableOutput);
|
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorConfig()->motorPwmRate, enableOutput);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
case PWM_TYPE_DSHOT1200:
|
|
||||||
case PWM_TYPE_DSHOT600:
|
case PWM_TYPE_DSHOT600:
|
||||||
case PWM_TYPE_DSHOT300:
|
case PWM_TYPE_DSHOT300:
|
||||||
case PWM_TYPE_DSHOT150:
|
case PWM_TYPE_DSHOT150:
|
||||||
|
|
|
@ -27,13 +27,6 @@
|
||||||
|
|
||||||
struct rangefinderDev_s;
|
struct rangefinderDev_s;
|
||||||
|
|
||||||
typedef struct rangefinderHardwarePins_s {
|
|
||||||
ioTag_t triggerTag;
|
|
||||||
ioTag_t echoTag;
|
|
||||||
} rangefinderHardwarePins_t;
|
|
||||||
|
|
||||||
struct rangefinderDev_s;
|
|
||||||
|
|
||||||
typedef void (*rangefinderOpInitFuncPtr)(struct rangefinderDev_s * dev);
|
typedef void (*rangefinderOpInitFuncPtr)(struct rangefinderDev_s * dev);
|
||||||
typedef void (*rangefinderOpStartFuncPtr)(struct rangefinderDev_s * dev);
|
typedef void (*rangefinderOpStartFuncPtr)(struct rangefinderDev_s * dev);
|
||||||
typedef int32_t (*rangefinderOpReadFuncPtr)(struct rangefinderDev_s * dev);
|
typedef int32_t (*rangefinderOpReadFuncPtr)(struct rangefinderDev_s * dev);
|
||||||
|
|
|
@ -1,221 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight 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.
|
|
||||||
*
|
|
||||||
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#include <platform.h>
|
|
||||||
|
|
||||||
#if defined(USE_RANGEFINDER_HCSR04)
|
|
||||||
|
|
||||||
#include "build/build_config.h"
|
|
||||||
|
|
||||||
#include "common/time.h"
|
|
||||||
|
|
||||||
#include "drivers/time.h"
|
|
||||||
#include "drivers/exti.h"
|
|
||||||
#include "drivers/io.h"
|
|
||||||
#include "drivers/nvic.h"
|
|
||||||
#include "drivers/rcc.h"
|
|
||||||
|
|
||||||
#include "drivers/rangefinder/rangefinder.h"
|
|
||||||
#include "drivers/rangefinder/rangefinder_hcsr04.h"
|
|
||||||
|
|
||||||
#define HCSR04_MAX_RANGE_CM 400 // 4m, from HC-SR04 spec sheet
|
|
||||||
#define HCSR04_DETECTION_CONE_DECIDEGREES 300 // recommended cone angle30 degrees, from HC-SR04 spec sheet
|
|
||||||
#define HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES 450 // in practice 45 degrees seems to work well
|
|
||||||
|
|
||||||
|
|
||||||
/* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits.
|
|
||||||
* When triggered it sends out a series of 40KHz ultrasonic pulses and receives
|
|
||||||
* echo from an object. The distance between the unit and the object is calculated
|
|
||||||
* by measuring the traveling time of sound and output it as the width of a TTL pulse.
|
|
||||||
*
|
|
||||||
* *** Warning: HC-SR04 operates at +5V ***
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
static volatile timeDelta_t hcsr04SonarPulseTravelTime = 0;
|
|
||||||
static volatile timeMs_t lastMeasurementReceivedAt;
|
|
||||||
static volatile int32_t lastCalculatedDistance = RANGEFINDER_OUT_OF_RANGE;
|
|
||||||
static timeMs_t lastMeasurementStartedAt = 0;
|
|
||||||
|
|
||||||
#ifdef USE_EXTI
|
|
||||||
static extiCallbackRec_t hcsr04_extiCallbackRec;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static IO_t echoIO;
|
|
||||||
static IO_t triggerIO;
|
|
||||||
|
|
||||||
#if !defined(UNIT_TEST)
|
|
||||||
void hcsr04_extiHandler(extiCallbackRec_t* cb)
|
|
||||||
{
|
|
||||||
static timeUs_t timing_start;
|
|
||||||
UNUSED(cb);
|
|
||||||
|
|
||||||
if (IORead(echoIO) != 0) {
|
|
||||||
timing_start = micros();
|
|
||||||
} else {
|
|
||||||
const timeUs_t timing_stop = micros();
|
|
||||||
if (timing_stop > timing_start) {
|
|
||||||
lastMeasurementReceivedAt = millis();
|
|
||||||
hcsr04SonarPulseTravelTime = timing_stop - timing_start;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void hcsr04_init(rangefinderDev_t *dev)
|
|
||||||
{
|
|
||||||
UNUSED(dev);
|
|
||||||
}
|
|
||||||
|
|
||||||
#define HCSR04_MinimumFiringIntervalMs 60
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Start a range reading
|
|
||||||
* Called periodically by the scheduler
|
|
||||||
* Measurement reading is done asynchronously, using interrupt
|
|
||||||
*/
|
|
||||||
void hcsr04_start_reading(void)
|
|
||||||
{
|
|
||||||
#if !defined(UNIT_TEST)
|
|
||||||
#ifdef RANGEFINDER_HCSR04_TRIG_INVERTED
|
|
||||||
IOLo(triggerIO);
|
|
||||||
delayMicroseconds(11);
|
|
||||||
IOHi(triggerIO);
|
|
||||||
#else
|
|
||||||
IOHi(triggerIO);
|
|
||||||
delayMicroseconds(11);
|
|
||||||
IOLo(triggerIO);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void hcsr04_update(rangefinderDev_t *dev)
|
|
||||||
{
|
|
||||||
UNUSED(dev);
|
|
||||||
const timeMs_t timeNowMs = millis();
|
|
||||||
|
|
||||||
// the firing interval of the trigger signal should be greater than 60ms
|
|
||||||
// to avoid interference between consecutive measurements
|
|
||||||
if (timeNowMs > lastMeasurementStartedAt + HCSR04_MinimumFiringIntervalMs) {
|
|
||||||
// We should have a valid measurement within 60ms of trigger
|
|
||||||
if ((lastMeasurementReceivedAt - lastMeasurementStartedAt) <= HCSR04_MinimumFiringIntervalMs) {
|
|
||||||
// The speed of sound is 340 m/s or approx. 29 microseconds per centimeter.
|
|
||||||
// The ping travels out and back, so to find the distance of the
|
|
||||||
// object we take half of the distance traveled.
|
|
||||||
// 340 m/s = 0.034 cm/microsecond = 29.41176471 *2 = 58.82352941 rounded to 59
|
|
||||||
|
|
||||||
lastCalculatedDistance = hcsr04SonarPulseTravelTime / 59;
|
|
||||||
if (lastCalculatedDistance > HCSR04_MAX_RANGE_CM) {
|
|
||||||
lastCalculatedDistance = RANGEFINDER_OUT_OF_RANGE;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
// No measurement within reasonable time - indicate failure
|
|
||||||
lastCalculatedDistance = RANGEFINDER_HARDWARE_FAILURE;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Trigger a new measurement
|
|
||||||
lastMeasurementStartedAt = timeNowMs;
|
|
||||||
hcsr04_start_reading();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Get the distance that was measured by the last pulse, in centimeters.
|
|
||||||
*/
|
|
||||||
int32_t hcsr04_get_distance(rangefinderDev_t *dev)
|
|
||||||
{
|
|
||||||
UNUSED(dev);
|
|
||||||
return lastCalculatedDistance;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool hcsr04Detect(rangefinderDev_t *dev, const rangefinderHardwarePins_t * rangefinderHardwarePins)
|
|
||||||
{
|
|
||||||
bool detected = false;
|
|
||||||
|
|
||||||
#if defined(STM32F3) || defined(STM32F4)
|
|
||||||
RCC_ClockCmd(RCC_APB2(SYSCFG), ENABLE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
triggerIO = IOGetByTag(rangefinderHardwarePins->triggerTag);
|
|
||||||
echoIO = IOGetByTag(rangefinderHardwarePins->echoTag);
|
|
||||||
|
|
||||||
if (IOGetOwner(triggerIO) != OWNER_FREE) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (IOGetOwner(echoIO) != OWNER_FREE) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// trigger pin
|
|
||||||
IOInit(triggerIO, OWNER_RANGEFINDER, RESOURCE_OUTPUT, 0);
|
|
||||||
IOConfigGPIO(triggerIO, IOCFG_OUT_PP);
|
|
||||||
IOLo(triggerIO);
|
|
||||||
delay(100);
|
|
||||||
|
|
||||||
// echo pin
|
|
||||||
IOInit(echoIO, OWNER_RANGEFINDER, RESOURCE_INPUT, 0);
|
|
||||||
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
|
|
||||||
|
|
||||||
// HC-SR04 echo line should be low by default and should return a response pulse when triggered
|
|
||||||
if (IORead(echoIO) == false) {
|
|
||||||
for (int i = 0; i < 5 && !detected; i++) {
|
|
||||||
timeMs_t requestTime = millis();
|
|
||||||
hcsr04_start_reading();
|
|
||||||
|
|
||||||
while ((millis() - requestTime) < HCSR04_MinimumFiringIntervalMs) {
|
|
||||||
if (IORead(echoIO) == true) {
|
|
||||||
detected = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (detected) {
|
|
||||||
// Hardware detected - configure the driver
|
|
||||||
#ifdef USE_EXTI
|
|
||||||
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
|
|
||||||
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority!
|
|
||||||
EXTIEnable(echoIO, true);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
dev->delayMs = 100;
|
|
||||||
dev->maxRangeCm = HCSR04_MAX_RANGE_CM;
|
|
||||||
dev->detectionConeDeciDegrees = HCSR04_DETECTION_CONE_DECIDEGREES;
|
|
||||||
dev->detectionConeExtendedDeciDegrees = HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES;
|
|
||||||
|
|
||||||
dev->init = &hcsr04_init;
|
|
||||||
dev->update = &hcsr04_update;
|
|
||||||
dev->read = &hcsr04_get_distance;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
// Not detected - free resources
|
|
||||||
IORelease(triggerIO);
|
|
||||||
IORelease(echoIO);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
|
@ -1,24 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight 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.
|
|
||||||
*
|
|
||||||
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include "drivers/rangefinder/rangefinder.h"
|
|
||||||
|
|
||||||
#define RANGEFINDER_HCSR04_TASK_PERIOD_MS 70
|
|
||||||
|
|
||||||
bool hcsr04Detect(rangefinderDev_t *dev, const rangefinderHardwarePins_t * rangefinderHardwarePins);
|
|
|
@ -265,9 +265,6 @@ void validateAndFixConfig(void)
|
||||||
case PWM_TYPE_ONESHOT125: // Limited to 3900 Hz
|
case PWM_TYPE_ONESHOT125: // Limited to 3900 Hz
|
||||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 3900);
|
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 3900);
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_ONESHOT42: // 2-8 kHz
|
|
||||||
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 8000);
|
|
||||||
break;
|
|
||||||
case PWM_TYPE_MULTISHOT: // 2-16 kHz
|
case PWM_TYPE_MULTISHOT: // 2-16 kHz
|
||||||
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 16000);
|
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 16000);
|
||||||
break;
|
break;
|
||||||
|
@ -287,14 +284,6 @@ void validateAndFixConfig(void)
|
||||||
case PWM_TYPE_DSHOT600:
|
case PWM_TYPE_DSHOT600:
|
||||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 16000);
|
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 16000);
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_DSHOT1200:
|
|
||||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 32000);
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_SERIALSHOT
|
|
||||||
case PWM_TYPE_SERIALSHOT: // 2-4 kHz
|
|
||||||
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 4000);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -929,7 +929,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
mixTable(dT);
|
mixTable();
|
||||||
|
|
||||||
if (isMixerUsingServos()) {
|
if (isMixerUsingServos()) {
|
||||||
servoMixer(dT);
|
servoMixer(dT);
|
||||||
|
|
|
@ -364,20 +364,6 @@ void init(void)
|
||||||
updateHardwareRevision();
|
updateHardwareRevision();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_RANGEFINDER_HCSR04) && defined(USE_SOFTSERIAL1)
|
|
||||||
#if defined(FURYF3) || defined(OMNIBUS) || defined(SPRACINGF3MINI)
|
|
||||||
if ((rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) && feature(FEATURE_SOFTSERIAL)) {
|
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_RANGEFINDER_HCSR04) && defined(USE_SOFTSERIAL2) && defined(SPRACINGF3)
|
|
||||||
if ((rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) && feature(FEATURE_SOFTSERIAL)) {
|
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_USB_MSC
|
#ifdef USE_USB_MSC
|
||||||
/* MSC mode will start after init, but will not allow scheduler to run,
|
/* MSC mode will start after init, but will not allow scheduler to run,
|
||||||
* so there is no bottleneck in reading and writing data
|
* so there is no bottleneck in reading and writing data
|
||||||
|
|
|
@ -7,13 +7,13 @@ tables:
|
||||||
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "FAKE"]
|
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "FAKE"]
|
||||||
enum: accelerationSensor_e
|
enum: accelerationSensor_e
|
||||||
- name: rangefinder_hardware
|
- name: rangefinder_hardware
|
||||||
values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UNUSED", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"]
|
values: ["NONE", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"]
|
||||||
enum: rangefinderType_e
|
enum: rangefinderType_e
|
||||||
- name: secondary_imu_hardware
|
- name: secondary_imu_hardware
|
||||||
values: ["NONE", "BNO055", "BNO055_SERIAL"]
|
values: ["NONE", "BNO055", "BNO055_SERIAL"]
|
||||||
enum: secondaryImuType_e
|
enum: secondaryImuType_e
|
||||||
- name: mag_hardware
|
- name: mag_hardware
|
||||||
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "FAKE"]
|
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "FAKE"]
|
||||||
enum: magSensor_e
|
enum: magSensor_e
|
||||||
- name: opflow_hardware
|
- name: opflow_hardware
|
||||||
values: ["NONE", "CXOF", "MSP", "FAKE"]
|
values: ["NONE", "CXOF", "MSP", "FAKE"]
|
||||||
|
@ -35,7 +35,7 @@ tables:
|
||||||
- name: blackbox_device
|
- name: blackbox_device
|
||||||
values: ["SERIAL", "SPIFLASH", "SDCARD"]
|
values: ["SERIAL", "SPIFLASH", "SDCARD"]
|
||||||
- name: motor_pwm_protocol
|
- name: motor_pwm_protocol
|
||||||
values: ["STANDARD", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200", "SERIALSHOT"]
|
values: ["STANDARD", "ONESHOT125", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600"]
|
||||||
- name: servo_protocol
|
- name: servo_protocol
|
||||||
values: ["PWM", "SERVO_DRIVER", "SBUS", "SBUS_PWM"]
|
values: ["PWM", "SERVO_DRIVER", "SBUS", "SBUS_PWM"]
|
||||||
- name: failsafe_procedure
|
- name: failsafe_procedure
|
||||||
|
@ -861,18 +861,6 @@ groups:
|
||||||
field: motorPwmRate
|
field: motorPwmRate
|
||||||
min: 50
|
min: 50
|
||||||
max: 32000
|
max: 32000
|
||||||
- name: motor_accel_time
|
|
||||||
description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]"
|
|
||||||
default_value: 0
|
|
||||||
field: motorAccelTimeMs
|
|
||||||
min: 0
|
|
||||||
max: 1000
|
|
||||||
- name: motor_decel_time
|
|
||||||
description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]"
|
|
||||||
default_value: 0
|
|
||||||
field: motorDecelTimeMs
|
|
||||||
min: 0
|
|
||||||
max: 1000
|
|
||||||
- name: motor_pwm_protocol
|
- name: motor_pwm_protocol
|
||||||
description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED"
|
description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED"
|
||||||
default_value: "ONESHOT125"
|
default_value: "ONESHOT125"
|
||||||
|
|
|
@ -102,15 +102,13 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
|
||||||
|
|
||||||
#define DEFAULT_MAX_THROTTLE 1850
|
#define DEFAULT_MAX_THROTTLE 1850
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 8);
|
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 9);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
|
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
|
||||||
.motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT,
|
.motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT,
|
||||||
.motorPwmRate = SETTING_MOTOR_PWM_RATE_DEFAULT,
|
.motorPwmRate = SETTING_MOTOR_PWM_RATE_DEFAULT,
|
||||||
.maxthrottle = SETTING_MAX_THROTTLE_DEFAULT,
|
.maxthrottle = SETTING_MAX_THROTTLE_DEFAULT,
|
||||||
.mincommand = SETTING_MIN_COMMAND_DEFAULT,
|
.mincommand = SETTING_MIN_COMMAND_DEFAULT,
|
||||||
.motorAccelTimeMs = SETTING_MOTOR_ACCEL_TIME_DEFAULT,
|
|
||||||
.motorDecelTimeMs = SETTING_MOTOR_DECEL_TIME_DEFAULT,
|
|
||||||
.motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles
|
.motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles
|
||||||
);
|
);
|
||||||
|
|
||||||
|
@ -118,9 +116,6 @@ PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTO
|
||||||
|
|
||||||
#define CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN 0.15f
|
#define CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN 0.15f
|
||||||
|
|
||||||
typedef void (*motorRateLimitingApplyFnPtr)(const float dT);
|
|
||||||
static EXTENDED_FASTRAM motorRateLimitingApplyFnPtr motorRateLimitingApplyFn;
|
|
||||||
|
|
||||||
int getThrottleIdleValue(void)
|
int getThrottleIdleValue(void)
|
||||||
{
|
{
|
||||||
if (!throttleIdleValue) {
|
if (!throttleIdleValue) {
|
||||||
|
@ -201,44 +196,6 @@ void nullMotorRateLimiting(const float dT)
|
||||||
UNUSED(dT);
|
UNUSED(dT);
|
||||||
}
|
}
|
||||||
|
|
||||||
void applyMotorRateLimiting(const float dT)
|
|
||||||
{
|
|
||||||
static float motorPrevious[MAX_SUPPORTED_MOTORS] = { 0 };
|
|
||||||
|
|
||||||
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
|
||||||
// FIXME: Don't apply rate limiting in 3D mode
|
|
||||||
for (int i = 0; i < motorCount; i++) {
|
|
||||||
motorPrevious[i] = motor[i];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
// Calculate max motor step
|
|
||||||
const uint16_t motorRange = motorConfig()->maxthrottle - throttleIdleValue;
|
|
||||||
const float motorMaxInc = (motorConfig()->motorAccelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorAccelTimeMs * 1e-3f);
|
|
||||||
const float motorMaxDec = (motorConfig()->motorDecelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorDecelTimeMs * 1e-3f);
|
|
||||||
|
|
||||||
for (int i = 0; i < motorCount; i++) {
|
|
||||||
// Apply motor rate limiting
|
|
||||||
motorPrevious[i] = constrainf(motor[i], motorPrevious[i] - motorMaxDec, motorPrevious[i] + motorMaxInc);
|
|
||||||
|
|
||||||
// Handle throttle below min_throttle (motor start/stop)
|
|
||||||
if (motorPrevious[i] < throttleIdleValue) {
|
|
||||||
if (motor[i] < throttleIdleValue) {
|
|
||||||
motorPrevious[i] = motor[i];
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
motorPrevious[i] = throttleIdleValue;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Update motor values
|
|
||||||
for (int i = 0; i < motorCount; i++) {
|
|
||||||
motor[i] = motorPrevious[i];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void mixerInit(void)
|
void mixerInit(void)
|
||||||
{
|
{
|
||||||
computeMotorCount();
|
computeMotorCount();
|
||||||
|
@ -253,12 +210,6 @@ void mixerInit(void)
|
||||||
|
|
||||||
mixerResetDisarmedMotors();
|
mixerResetDisarmedMotors();
|
||||||
|
|
||||||
if (motorConfig()->motorAccelTimeMs || motorConfig()->motorDecelTimeMs) {
|
|
||||||
motorRateLimitingApplyFn = applyMotorRateLimiting;
|
|
||||||
} else {
|
|
||||||
motorRateLimitingApplyFn = nullMotorRateLimiting;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (mixerConfig()->motorDirectionInverted) {
|
if (mixerConfig()->motorDirectionInverted) {
|
||||||
motorYawMultiplier = -1;
|
motorYawMultiplier = -1;
|
||||||
} else {
|
} else {
|
||||||
|
@ -516,7 +467,7 @@ static int getReversibleMotorsThrottleDeadband(void)
|
||||||
return feature(FEATURE_MOTOR_STOP) ? reversibleMotorsConfig()->neutral : directionValue;
|
return feature(FEATURE_MOTOR_STOP) ? reversibleMotorsConfig()->neutral : directionValue;
|
||||||
}
|
}
|
||||||
|
|
||||||
void FAST_CODE mixTable(const float dT)
|
void FAST_CODE mixTable()
|
||||||
{
|
{
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
if (FLIGHT_MODE(TURTLE_MODE)) {
|
if (FLIGHT_MODE(TURTLE_MODE)) {
|
||||||
|
@ -649,9 +600,6 @@ void FAST_CODE mixTable(const float dT)
|
||||||
motor[i] = motor_disarmed[i];
|
motor[i] = motor_disarmed[i];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Apply motor acceleration/deceleration limit */
|
|
||||||
motorRateLimitingApplyFn(dT);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t getThrottlePercent(void)
|
int16_t getThrottlePercent(void)
|
||||||
|
|
|
@ -80,8 +80,6 @@ typedef struct motorConfig_s {
|
||||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||||
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
|
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
|
||||||
uint8_t motorPwmProtocol;
|
uint8_t motorPwmProtocol;
|
||||||
uint16_t motorAccelTimeMs; // Time limit for motor to accelerate from 0 to 100% throttle [ms]
|
|
||||||
uint16_t motorDecelTimeMs; // Time limit for motor to decelerate from 0 to 100% throttle [ms]
|
|
||||||
uint16_t digitalIdleOffsetValue;
|
uint16_t digitalIdleOffsetValue;
|
||||||
uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry
|
uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry
|
||||||
} motorConfig_t;
|
} motorConfig_t;
|
||||||
|
@ -115,7 +113,7 @@ void writeAllMotors(int16_t mc);
|
||||||
void mixerInit(void);
|
void mixerInit(void);
|
||||||
void mixerUpdateStateFlags(void);
|
void mixerUpdateStateFlags(void);
|
||||||
void mixerResetDisarmedMotors(void);
|
void mixerResetDisarmedMotors(void);
|
||||||
void mixTable(const float dT);
|
void mixTable(void);
|
||||||
void writeMotors(void);
|
void writeMotors(void);
|
||||||
void processServoAutotrim(const float dT);
|
void processServoAutotrim(const float dT);
|
||||||
void processServoAutotrimMode(void);
|
void processServoAutotrimMode(void);
|
||||||
|
|
|
@ -1,116 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of INAV Project.
|
|
||||||
*
|
|
||||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
|
||||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
|
||||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
|
||||||
*
|
|
||||||
* Alternatively, the contents of this file may be used under the terms
|
|
||||||
* of the GNU General Public License Version 3, as described below:
|
|
||||||
*
|
|
||||||
* This file is free software: you may copy, redistribute 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.
|
|
||||||
*
|
|
||||||
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <ctype.h>
|
|
||||||
#include <math.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#include "build/build_config.h"
|
|
||||||
#include "build/debug.h"
|
|
||||||
|
|
||||||
#include "common/maths.h"
|
|
||||||
#include "common/crc.h"
|
|
||||||
|
|
||||||
#include "io/serial.h"
|
|
||||||
#include "io/esc_serialshot.h"
|
|
||||||
|
|
||||||
#if defined(USE_SERIALSHOT)
|
|
||||||
|
|
||||||
#define SERIALSHOT_UART_BAUD 921600
|
|
||||||
#define SERIALSHOT_PKT_DEFAULT_HEADER (0x00) // Default header (motors 1-4, regular 4-in-1 ESC)
|
|
||||||
|
|
||||||
|
|
||||||
typedef struct __attribute__((packed)) {
|
|
||||||
uint8_t hdr; // Header/version marker
|
|
||||||
uint8_t motorData[6]; // 12 bit per motor
|
|
||||||
uint8_t crc; // CRC8/DVB-T of hdr & motorData
|
|
||||||
} serialShortPacket_t;
|
|
||||||
|
|
||||||
|
|
||||||
static serialShortPacket_t txPkt;
|
|
||||||
static uint16_t motorValues[4];
|
|
||||||
static serialPort_t * escPort = NULL;
|
|
||||||
static serialPortConfig_t * portConfig;
|
|
||||||
|
|
||||||
bool serialshotInitialize(void)
|
|
||||||
{
|
|
||||||
// Avoid double initialization
|
|
||||||
if (escPort) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
portConfig = findSerialPortConfig(FUNCTION_ESCSERIAL);
|
|
||||||
if (!portConfig) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
escPort = openSerialPort(portConfig->identifier, FUNCTION_ESCSERIAL, NULL, NULL, SERIALSHOT_UART_BAUD, MODE_RXTX, SERIAL_NOT_INVERTED | SERIAL_UNIDIR);
|
|
||||||
if (!escPort) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void serialshotUpdateMotor(int index, uint16_t value)
|
|
||||||
{
|
|
||||||
if (index < 0 || index > 3) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
motorValues[index] = value;
|
|
||||||
}
|
|
||||||
|
|
||||||
void serialshotSendUpdate(void)
|
|
||||||
{
|
|
||||||
// Check if the port is initialized
|
|
||||||
if (!escPort) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Skip update if previous one is not yet fully sent
|
|
||||||
// This helps to avoid buffer overflow and evenyually the data corruption
|
|
||||||
if (!isSerialTransmitBufferEmpty(escPort)) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
txPkt.hdr = SERIALSHOT_PKT_DEFAULT_HEADER;
|
|
||||||
|
|
||||||
txPkt.motorData[0] = motorValues[0] & 0x00FF;
|
|
||||||
txPkt.motorData[1] = motorValues[1] & 0x00FF;
|
|
||||||
txPkt.motorData[2] = motorValues[2] & 0x00FF;
|
|
||||||
txPkt.motorData[3] = motorValues[3] & 0x00FF;
|
|
||||||
txPkt.motorData[4] = (((motorValues[0] & 0xF00) >> 8) << 0) | (((motorValues[1] & 0xF00) >> 8) << 4);
|
|
||||||
txPkt.motorData[5] = (((motorValues[2] & 0xF00) >> 8) << 0) | (((motorValues[3] & 0xF00) >> 8) << 4);
|
|
||||||
|
|
||||||
txPkt.crc = crc8_dvb_s2(0x00, txPkt.hdr);
|
|
||||||
txPkt.crc = crc8_dvb_s2_update(txPkt.crc, txPkt.motorData, sizeof(txPkt.motorData));
|
|
||||||
|
|
||||||
serialWriteBuf(escPort, (const uint8_t *)&txPkt, sizeof(txPkt));
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
|
@ -7,6 +7,9 @@
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_PWM_SERVO_DRIVER
|
||||||
|
|
||||||
#define PWM_DRIVER_IMPLEMENTATION_COUNT 1
|
#define PWM_DRIVER_IMPLEMENTATION_COUNT 1
|
||||||
#define PWM_DRIVER_MAX_CYCLE 4
|
#define PWM_DRIVER_MAX_CYCLE 4
|
||||||
|
@ -63,3 +66,5 @@ void pwmDriverSync(void) {
|
||||||
cycle = 0;
|
cycle = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
|
@ -41,6 +41,7 @@
|
||||||
#include "drivers/compass/compass_mpu9250.h"
|
#include "drivers/compass/compass_mpu9250.h"
|
||||||
#include "drivers/compass/compass_lis3mdl.h"
|
#include "drivers/compass/compass_lis3mdl.h"
|
||||||
#include "drivers/compass/compass_rm3100.h"
|
#include "drivers/compass/compass_rm3100.h"
|
||||||
|
#include "drivers/compass/compass_vcm5883.h"
|
||||||
#include "drivers/compass/compass_msp.h"
|
#include "drivers/compass/compass_msp.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
@ -62,7 +63,7 @@ mag_t mag; // mag access functions
|
||||||
|
|
||||||
#ifdef USE_MAG
|
#ifdef USE_MAG
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 4);
|
PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 5);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(compassConfig_t, compassConfig,
|
PG_RESET_TEMPLATE(compassConfig_t, compassConfig,
|
||||||
.mag_align = SETTING_ALIGN_MAG_DEFAULT,
|
.mag_align = SETTING_ALIGN_MAG_DEFAULT,
|
||||||
|
@ -246,6 +247,19 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
|
||||||
}
|
}
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
|
|
||||||
|
case MAG_VCM5883:
|
||||||
|
#ifdef USE_MAG_VCM5883
|
||||||
|
if (vcm5883Detect(dev)) {
|
||||||
|
magHardware = MAG_VCM5883;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
|
||||||
|
if (magHardwareToUse != MAG_AUTODETECT) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
FALLTHROUGH;
|
||||||
|
|
||||||
case MAG_FAKE:
|
case MAG_FAKE:
|
||||||
#ifdef USE_FAKE_MAG
|
#ifdef USE_FAKE_MAG
|
||||||
if (fakeMagDetect(dev)) {
|
if (fakeMagDetect(dev)) {
|
||||||
|
|
|
@ -42,7 +42,8 @@ typedef enum {
|
||||||
MAG_LIS3MDL = 11,
|
MAG_LIS3MDL = 11,
|
||||||
MAG_MSP = 12,
|
MAG_MSP = 12,
|
||||||
MAG_RM3100 = 13,
|
MAG_RM3100 = 13,
|
||||||
MAG_FAKE = 14,
|
MAG_VCM5883 = 14,
|
||||||
|
MAG_FAKE = 15,
|
||||||
MAG_MAX = MAG_FAKE
|
MAG_MAX = MAG_FAKE
|
||||||
} magSensor_e;
|
} magSensor_e;
|
||||||
|
|
||||||
|
|
|
@ -36,7 +36,6 @@
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/rangefinder/rangefinder.h"
|
#include "drivers/rangefinder/rangefinder.h"
|
||||||
#include "drivers/rangefinder/rangefinder_hcsr04.h"
|
|
||||||
#include "drivers/rangefinder/rangefinder_srf10.h"
|
#include "drivers/rangefinder/rangefinder_srf10.h"
|
||||||
#include "drivers/rangefinder/rangefinder_hcsr04_i2c.h"
|
#include "drivers/rangefinder/rangefinder_hcsr04_i2c.h"
|
||||||
#include "drivers/rangefinder/rangefinder_vl53l0x.h"
|
#include "drivers/rangefinder/rangefinder_vl53l0x.h"
|
||||||
|
@ -65,28 +64,13 @@ rangefinder_t rangefinder;
|
||||||
#define RANGEFINDER_DYNAMIC_FACTOR 75
|
#define RANGEFINDER_DYNAMIC_FACTOR 75
|
||||||
|
|
||||||
#ifdef USE_RANGEFINDER
|
#ifdef USE_RANGEFINDER
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 1);
|
PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 2);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig,
|
PG_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig,
|
||||||
.rangefinder_hardware = SETTING_RANGEFINDER_HARDWARE_DEFAULT,
|
.rangefinder_hardware = SETTING_RANGEFINDER_HARDWARE_DEFAULT,
|
||||||
.use_median_filtering = SETTING_RANGEFINDER_MEDIAN_FILTER_DEFAULT,
|
.use_median_filtering = SETTING_RANGEFINDER_MEDIAN_FILTER_DEFAULT,
|
||||||
);
|
);
|
||||||
|
|
||||||
const rangefinderHardwarePins_t * rangefinderGetHardwarePins(void)
|
|
||||||
{
|
|
||||||
static rangefinderHardwarePins_t rangefinderHardwarePins;
|
|
||||||
|
|
||||||
#if defined(RANGEFINDER_HCSR04_TRIGGER_PIN)
|
|
||||||
rangefinderHardwarePins.triggerTag = IO_TAG(RANGEFINDER_HCSR04_TRIGGER_PIN);
|
|
||||||
rangefinderHardwarePins.echoTag = IO_TAG(RANGEFINDER_HCSR04_ECHO_PIN);
|
|
||||||
#else
|
|
||||||
// No Trig/Echo hardware rangefinder
|
|
||||||
rangefinderHardwarePins.triggerTag = IO_TAG(NONE);
|
|
||||||
rangefinderHardwarePins.echoTag = IO_TAG(NONE);
|
|
||||||
#endif
|
|
||||||
return &rangefinderHardwarePins;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Detect which rangefinder is present
|
* Detect which rangefinder is present
|
||||||
*/
|
*/
|
||||||
|
@ -96,18 +80,6 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar
|
||||||
requestedSensors[SENSOR_INDEX_RANGEFINDER] = rangefinderHardwareToUse;
|
requestedSensors[SENSOR_INDEX_RANGEFINDER] = rangefinderHardwareToUse;
|
||||||
|
|
||||||
switch (rangefinderHardwareToUse) {
|
switch (rangefinderHardwareToUse) {
|
||||||
case RANGEFINDER_HCSR04:
|
|
||||||
#ifdef USE_RANGEFINDER_HCSR04
|
|
||||||
{
|
|
||||||
const rangefinderHardwarePins_t *rangefinderHardwarePins = rangefinderGetHardwarePins();
|
|
||||||
if (hcsr04Detect(dev, rangefinderHardwarePins)) { // FIXME: Do actual detection if HC-SR04 is plugged in
|
|
||||||
rangefinderHardware = RANGEFINDER_HCSR04;
|
|
||||||
rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_HCSR04_TASK_PERIOD_MS));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
|
|
||||||
case RANGEFINDER_SRF10:
|
case RANGEFINDER_SRF10:
|
||||||
#ifdef USE_RANGEFINDER_SRF10
|
#ifdef USE_RANGEFINDER_SRF10
|
||||||
if (srf10Detect(dev)) {
|
if (srf10Detect(dev)) {
|
||||||
|
|
|
@ -23,16 +23,14 @@
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
RANGEFINDER_NONE = 0,
|
RANGEFINDER_NONE = 0,
|
||||||
RANGEFINDER_HCSR04 = 1,
|
RANGEFINDER_SRF10 = 1,
|
||||||
RANGEFINDER_SRF10 = 2,
|
RANGEFINDER_HCSR04I2C = 2,
|
||||||
RANGEFINDER_HCSR04I2C = 3,
|
RANGEFINDER_VL53L0X = 3,
|
||||||
RANGEFINDER_VL53L0X = 4,
|
RANGEFINDER_MSP = 4,
|
||||||
RANGEFINDER_MSP = 5,
|
RANGEFINDER_BENEWAKE = 5,
|
||||||
RANGEFINDER_UNUSED = 6, // Was UIB
|
RANGEFINDER_VL53L1X = 6,
|
||||||
RANGEFINDER_BENEWAKE = 7,
|
RANGEFINDER_US42 = 7,
|
||||||
RANGEFINDER_VL53L1X = 8,
|
RANGEFINDER_TOF10102I2C = 8,
|
||||||
RANGEFINDER_US42 = 9,
|
|
||||||
RANGEFINDER_TOF10102I2C = 10,
|
|
||||||
} rangefinderType_e;
|
} rangefinderType_e;
|
||||||
|
|
||||||
typedef struct rangefinderConfig_s {
|
typedef struct rangefinderConfig_s {
|
||||||
|
@ -52,8 +50,6 @@ typedef struct rangefinder_s {
|
||||||
|
|
||||||
extern rangefinder_t rangefinder;
|
extern rangefinder_t rangefinder;
|
||||||
|
|
||||||
const rangefinderHardwarePins_t * rangefinderGetHardwarePins(void);
|
|
||||||
|
|
||||||
bool rangefinderInit(void);
|
bool rangefinderInit(void);
|
||||||
|
|
||||||
int32_t rangefinderGetLatestAltitude(void);
|
int32_t rangefinderGetLatestAltitude(void);
|
||||||
|
|
|
@ -163,4 +163,3 @@
|
||||||
// ESC-related features
|
// ESC-related features
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
|
@ -115,6 +115,7 @@
|
||||||
|
|
||||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||||
#define BNO055_I2C_BUS BUS_I2C2
|
#define BNO055_I2C_BUS BUS_I2C2
|
||||||
|
#define MAG_I2C_BUS BUS_I2C2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
|
@ -124,9 +124,6 @@
|
||||||
|
|
||||||
#define USE_RANGEFINDER
|
#define USE_RANGEFINDER
|
||||||
#define RANGEFINDER_I2C_BUS BUS_I2C3
|
#define RANGEFINDER_I2C_BUS BUS_I2C3
|
||||||
#define USE_RANGEFINDER_HCSR04
|
|
||||||
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB8
|
|
||||||
#define RANGEFINDER_HCSR04_ECHO_PIN PB9
|
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
|
|
||||||
|
|
|
@ -138,7 +138,6 @@
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 6
|
#define MAX_PWM_OUTPUT_PORTS 6
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -117,9 +117,6 @@
|
||||||
#define BIND_PIN PA3
|
#define BIND_PIN PA3
|
||||||
|
|
||||||
#define USE_RANGEFINDER
|
#define USE_RANGEFINDER
|
||||||
#define USE_RANGEFINDER_HCSR04
|
|
||||||
#define RANGEFINDER_HCSR04_TRIGGER_PIN PA7
|
|
||||||
#define RANGEFINDER_HCSR04_ECHO_PIN PA2
|
|
||||||
|
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_GPS | FEATURE_TELEMETRY | FEATURE_LED_STRIP)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_GPS | FEATURE_TELEMETRY | FEATURE_LED_STRIP)
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
|
|
|
@ -42,6 +42,7 @@
|
||||||
|
|
||||||
#define USE_MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_MPU9250
|
#define USE_MAG_MPU9250
|
||||||
|
#define MAG_I2C_BUS BUS_I2C1
|
||||||
|
|
||||||
#define USE_BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
|
|
|
@ -147,9 +147,6 @@
|
||||||
|
|
||||||
// *************** RANGEFINDER *****************************
|
// *************** RANGEFINDER *****************************
|
||||||
// #define USE_RANGEFINDER
|
// #define USE_RANGEFINDER
|
||||||
// #define USE_RANGEFINDER_HCSR04
|
|
||||||
// #define RANGEFINDER_HCSR04_TRIGGER_PIN PB10
|
|
||||||
// #define RANGEFINDER_HCSR04_ECHO_PIN PB11
|
|
||||||
// #define USE_RANGEFINDER_SRF10
|
// #define USE_RANGEFINDER_SRF10
|
||||||
|
|
||||||
// *************** NAV *****************************
|
// *************** NAV *****************************
|
||||||
|
|
|
@ -165,7 +165,6 @@
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -150,4 +150,3 @@
|
||||||
#define MAX_PWM_OUTPUT_PORTS 5
|
#define MAX_PWM_OUTPUT_PORTS 5
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
|
@ -128,9 +128,6 @@
|
||||||
#define WS2811_PIN PA8
|
#define WS2811_PIN PA8
|
||||||
|
|
||||||
#define USE_RANGEFINDER
|
#define USE_RANGEFINDER
|
||||||
#define USE_RANGEFINDER_HCSR04
|
|
||||||
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
#define RANGEFINDER_HCSR04_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
|
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
||||||
|
|
|
@ -175,6 +175,5 @@
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 8
|
#define MAX_PWM_OUTPUT_PORTS 8
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
|
|
|
@ -171,7 +171,6 @@
|
||||||
#define TARGET_IO_PORTD (BIT(2))
|
#define TARGET_IO_PORTD (BIT(2))
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#ifdef KAKUTEF4V2
|
#ifdef KAKUTEF4V2
|
||||||
|
|
|
@ -160,7 +160,6 @@
|
||||||
#define MAX_PWM_OUTPUT_PORTS 6
|
#define MAX_PWM_OUTPUT_PORTS 6
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
||||||
#define USE_RANGEFINDER
|
#define USE_RANGEFINDER
|
||||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||||
|
|
|
@ -191,7 +191,6 @@
|
||||||
|
|
||||||
// ESC-related features
|
// ESC-related features
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
|
|
@ -193,7 +193,6 @@
|
||||||
|
|
||||||
// ESC-related features
|
// ESC-related features
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
|
|
@ -199,7 +199,6 @@
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 6
|
#define MAX_PWM_OUTPUT_PORTS 6
|
||||||
|
|
||||||
|
|
|
@ -160,7 +160,6 @@
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -163,7 +163,6 @@
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -157,6 +157,5 @@
|
||||||
#define MAX_PWM_OUTPUT_PORTS 7
|
#define MAX_PWM_OUTPUT_PORTS 7
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
||||||
#define BNO055_I2C_BUS BUS_I2C1
|
#define BNO055_I2C_BUS BUS_I2C1
|
||||||
|
|
|
@ -170,5 +170,4 @@
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 10
|
#define MAX_PWM_OUTPUT_PORTS 10
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
|
@ -191,7 +191,6 @@
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 8
|
#define MAX_PWM_OUTPUT_PORTS 8
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define BNO055_I2C_BUS BUS_I2C1
|
#define BNO055_I2C_BUS BUS_I2C1
|
||||||
|
|
|
@ -229,4 +229,3 @@
|
||||||
#define MAX_PWM_OUTPUT_PORTS 16
|
#define MAX_PWM_OUTPUT_PORTS 16
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
|
@ -205,5 +205,4 @@
|
||||||
#define MAX_PWM_OUTPUT_PORTS 15
|
#define MAX_PWM_OUTPUT_PORTS 15
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
||||||
|
|
|
@ -169,7 +169,6 @@
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
||||||
// Number of available PWM outputs
|
// Number of available PWM outputs
|
||||||
#define MAX_PWM_OUTPUT_PORTS 6
|
#define MAX_PWM_OUTPUT_PORTS 6
|
||||||
|
|
|
@ -90,9 +90,6 @@
|
||||||
#define WS2811_PIN PB8 // TIM16_CH1
|
#define WS2811_PIN PB8 // TIM16_CH1
|
||||||
|
|
||||||
#define USE_RANGEFINDER
|
#define USE_RANGEFINDER
|
||||||
#define USE_RANGEFINDER_HCSR04
|
|
||||||
#define RANGEFINDER_HCSR04_TRIGGER_PIN PA6 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
#define RANGEFINDER_HCSR04_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
|
|
||||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
|
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG)
|
||||||
|
|
||||||
|
|
|
@ -31,7 +31,6 @@
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
||||||
// MPU6000 interrupts
|
// MPU6000 interrupts
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -142,5 +142,4 @@
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 10
|
#define MAX_PWM_OUTPUT_PORTS 10
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_SERIALSHOT
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
|
@ -161,6 +161,5 @@
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 4
|
#define MAX_PWM_OUTPUT_PORTS 4
|
||||||
|
|
|
@ -92,9 +92,7 @@
|
||||||
#define BIND_PIN PA3
|
#define BIND_PIN PA3
|
||||||
|
|
||||||
// #define USE_RANGEFINDER
|
// #define USE_RANGEFINDER
|
||||||
// #define USE_RANGEFINDER_HCSR04
|
|
||||||
// #define RANGEFINDER_HCSR04_TRIGGER_PIN PA2 // PWM6 (PA2) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
// #define RANGEFINDER_HCSR04_ECHO_PIN PB1 // PWM7 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
|
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
||||||
|
|
||||||
|
|
|
@ -96,9 +96,6 @@
|
||||||
#define WS2811_PIN PA8
|
#define WS2811_PIN PA8
|
||||||
|
|
||||||
#define USE_RANGEFINDER
|
#define USE_RANGEFINDER
|
||||||
#define USE_RANGEFINDER_HCSR04
|
|
||||||
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0
|
|
||||||
#define RANGEFINDER_HCSR04_ECHO_PIN PB1
|
|
||||||
#define USE_RANGEFINDER_HCSR04_I2C
|
#define USE_RANGEFINDER_HCSR04_I2C
|
||||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||||
|
|
||||||
|
|
|
@ -231,4 +231,3 @@
|
||||||
#endif
|
#endif
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
#define USE_SERIALSHOT
|
|
||||||
|
|
|
@ -79,10 +79,14 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if (MCU_FLASH_SIZE > 256)
|
#if (MCU_FLASH_SIZE > 256)
|
||||||
|
|
||||||
|
#if defined(MAG_I2C_BUS) || defined(VCM5883_I2C_BUS)
|
||||||
|
#define USE_MAG_VCM5883
|
||||||
|
#endif
|
||||||
|
|
||||||
#define USE_MR_BRAKING_MODE
|
#define USE_MR_BRAKING_MODE
|
||||||
#define USE_PITOT
|
#define USE_PITOT
|
||||||
#define USE_PITOT_ADC
|
#define USE_PITOT_ADC
|
||||||
#define USE_PITOT_VIRTUAL
|
|
||||||
|
|
||||||
#define USE_ALPHA_BETA_GAMMA_FILTER
|
#define USE_ALPHA_BETA_GAMMA_FILTER
|
||||||
#define USE_DYNAMIC_FILTERS
|
#define USE_DYNAMIC_FILTERS
|
||||||
|
@ -90,7 +94,6 @@
|
||||||
#define USE_SMITH_PREDICTOR
|
#define USE_SMITH_PREDICTOR
|
||||||
#define USE_RATE_DYNAMICS
|
#define USE_RATE_DYNAMICS
|
||||||
#define USE_EXTENDED_CMS_MENUS
|
#define USE_EXTENDED_CMS_MENUS
|
||||||
#define USE_HOTT_TEXTMODE
|
|
||||||
|
|
||||||
// NAZA GPS support for F4+ only
|
// NAZA GPS support for F4+ only
|
||||||
#define USE_GPS_PROTO_NAZA
|
#define USE_GPS_PROTO_NAZA
|
||||||
|
@ -127,8 +130,6 @@
|
||||||
#define DASHBOARD_ARMED_BITMAP
|
#define DASHBOARD_ARMED_BITMAP
|
||||||
#define USE_OLED_UG2864
|
#define USE_OLED_UG2864
|
||||||
|
|
||||||
#define USE_PWM_DRIVER_PCA9685
|
|
||||||
|
|
||||||
#define USE_OSD
|
#define USE_OSD
|
||||||
#define USE_FRSKYOSD
|
#define USE_FRSKYOSD
|
||||||
#define USE_DJI_HD_OSD
|
#define USE_DJI_HD_OSD
|
||||||
|
@ -147,14 +148,10 @@
|
||||||
#define USE_GPS_PROTO_MTK
|
#define USE_GPS_PROTO_MTK
|
||||||
|
|
||||||
#define USE_TELEMETRY_SIM
|
#define USE_TELEMETRY_SIM
|
||||||
#define USE_TELEMETRY_HOTT
|
|
||||||
#define USE_TELEMETRY_MAVLINK
|
#define USE_TELEMETRY_MAVLINK
|
||||||
#define USE_MSP_OVER_TELEMETRY
|
#define USE_MSP_OVER_TELEMETRY
|
||||||
|
|
||||||
#define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
|
#define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
|
||||||
#define USE_SERIALRX_SUMD
|
|
||||||
#define USE_SERIALRX_SUMH
|
|
||||||
#define USE_SERIALRX_XBUS
|
|
||||||
#define USE_SERIALRX_JETIEXBUS
|
#define USE_SERIALRX_JETIEXBUS
|
||||||
#define USE_SERIALRX_MAVLINK
|
#define USE_SERIALRX_MAVLINK
|
||||||
#define USE_TELEMETRY_SRXL
|
#define USE_TELEMETRY_SRXL
|
||||||
|
@ -194,7 +191,6 @@
|
||||||
#define USE_RX_MSP
|
#define USE_RX_MSP
|
||||||
//#define USE_MSP_RC_OVERRIDE
|
//#define USE_MSP_RC_OVERRIDE
|
||||||
#define USE_SERIALRX_CRSF
|
#define USE_SERIALRX_CRSF
|
||||||
#define USE_PWM_SERVO_DRIVER
|
|
||||||
#define USE_SERIAL_PASSTHROUGH
|
#define USE_SERIAL_PASSTHROUGH
|
||||||
#define NAV_MAX_WAYPOINTS 60
|
#define NAV_MAX_WAYPOINTS 60
|
||||||
#define USE_RCDEVICE
|
#define USE_RCDEVICE
|
||||||
|
@ -203,7 +199,6 @@
|
||||||
#define USE_VTX_CONTROL
|
#define USE_VTX_CONTROL
|
||||||
#define USE_VTX_SMARTAUDIO
|
#define USE_VTX_SMARTAUDIO
|
||||||
#define USE_VTX_TRAMP
|
#define USE_VTX_TRAMP
|
||||||
#define USE_VTX_FFPV
|
|
||||||
|
|
||||||
#ifndef STM32F3 //F3 series does not have enoug RAM to support logic conditions
|
#ifndef STM32F3 //F3 series does not have enoug RAM to support logic conditions
|
||||||
#define USE_PROGRAMMING_FRAMEWORK
|
#define USE_PROGRAMMING_FRAMEWORK
|
||||||
|
@ -220,3 +215,19 @@
|
||||||
#define SKIP_TASK_STATISTICS
|
#define SKIP_TASK_STATISTICS
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//Designed to free space of F722 and F411 MCUs
|
||||||
|
#if (MCU_FLASH_SIZE > 512)
|
||||||
|
|
||||||
|
#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
|
||||||
|
#define USE_SERIALRX_XBUS
|
||||||
|
#define USE_TELEMETRY_HOTT
|
||||||
|
#define USE_HOTT_TEXTMODE
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -248,6 +248,14 @@
|
||||||
BUSDEV_REGISTER_SPI(busdev_rm3100, DEVHW_RM3100, RM3100_SPI_BUS, RM3100_CS_PIN, NONE, DEVFLAGS_NONE, 0);
|
BUSDEV_REGISTER_SPI(busdev_rm3100, DEVHW_RM3100, RM3100_SPI_BUS, RM3100_CS_PIN, NONE, DEVFLAGS_NONE, 0);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(USE_MAG_VCM5883)
|
||||||
|
#if !defined(VCM5883_I2C_BUS)
|
||||||
|
#define VCM5883_I2C_BUS MAG_I2C_BUS
|
||||||
|
#endif
|
||||||
|
BUSDEV_REGISTER_I2C(busdev_vcm5883, DEVHW_VCM5883, VCM5883_I2C_BUS, 0x0C, NONE, DEVFLAGS_NONE, 0);
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -58,7 +58,6 @@ extern uint8_t __config_end;
|
||||||
#undef USE_SERIALRX_SUMH
|
#undef USE_SERIALRX_SUMH
|
||||||
#undef USE_SERIALRX_XBUS
|
#undef USE_SERIALRX_XBUS
|
||||||
#undef USE_SERIALRX_JETIEXBUS
|
#undef USE_SERIALRX_JETIEXBUS
|
||||||
#undef USE_PWM_SERVO_DRIVER
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef BEEPER_PWM_FREQUENCY
|
#ifndef BEEPER_PWM_FREQUENCY
|
||||||
|
|
|
@ -1,107 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight 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.
|
|
||||||
*
|
|
||||||
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <math.h>
|
|
||||||
|
|
||||||
extern "C" {
|
|
||||||
#include "build_config.h"
|
|
||||||
#include "drivers/rangefinder_hcsr04.h"
|
|
||||||
#include "sensors/sonar.h"
|
|
||||||
extern int32_t measurement;
|
|
||||||
extern int16_t sonarMaxTiltDeciDegrees;
|
|
||||||
void sonarInit(const sonarHardware_t *sonarHardware);
|
|
||||||
}
|
|
||||||
|
|
||||||
#include "unittest_macros.h"
|
|
||||||
#include "gtest/gtest.h"
|
|
||||||
|
|
||||||
#define DECIDEGREES_TO_RADIANS(angle) ((angle / 10.0f) * 0.0174532925f)
|
|
||||||
|
|
||||||
TEST(SonarUnittest, TestConstants)
|
|
||||||
{
|
|
||||||
sonarInit(0);
|
|
||||||
// SONAR_OUT_OF_RANGE must be negative
|
|
||||||
EXPECT_LE(SONAR_OUT_OF_RANGE, 0);
|
|
||||||
// Check against gross errors in max range constants
|
|
||||||
EXPECT_GT(HCSR04_MAX_RANGE_CM, 100);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(SonarUnittest, TestSonarInit)
|
|
||||||
{
|
|
||||||
sonarInit(0);
|
|
||||||
// Check against gross errors in max range values
|
|
||||||
EXPECT_GE(sonarCfAltCm, 100);
|
|
||||||
EXPECT_LE(sonarCfAltCm, HCSR04_MAX_RANGE_CM);
|
|
||||||
// Check reasonable values for maximum tilt
|
|
||||||
EXPECT_GE(sonarMaxTiltDeciDegrees, 0);
|
|
||||||
EXPECT_LE(sonarMaxTiltDeciDegrees, 450);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(SonarUnittest, TestDistance)
|
|
||||||
{
|
|
||||||
// Check sonar pulse time converted correctly to cm
|
|
||||||
const int echoMicroSecondsPerCm = 59;
|
|
||||||
measurement = 0;
|
|
||||||
EXPECT_EQ(hcsr04_get_distance(), 0);
|
|
||||||
|
|
||||||
measurement = echoMicroSecondsPerCm;
|
|
||||||
EXPECT_EQ(hcsr04_get_distance(), 1);
|
|
||||||
|
|
||||||
measurement = 10 * echoMicroSecondsPerCm;
|
|
||||||
EXPECT_EQ(hcsr04_get_distance(), 10);
|
|
||||||
|
|
||||||
measurement = HCSR04_MAX_RANGE_CM * echoMicroSecondsPerCm;
|
|
||||||
EXPECT_EQ(hcsr04_get_distance(), HCSR04_MAX_RANGE_CM);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(SonarUnittest, TestAltitude)
|
|
||||||
{
|
|
||||||
sonarInit(0);
|
|
||||||
// Check distance not modified if no tilt
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(0, cosf(DECIDEGREES_TO_RADIANS(0))), 0);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), 0);
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(100, cosf(DECIDEGREES_TO_RADIANS(0))), 100);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), 100);
|
|
||||||
|
|
||||||
// Check that out of range is returned if tilt is too large
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(0, cosf(DECIDEGREES_TO_RADIANS(sonarMaxTiltDeciDegrees+1))), SONAR_OUT_OF_RANGE);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), SONAR_OUT_OF_RANGE);
|
|
||||||
|
|
||||||
// Check distance at various roll angles
|
|
||||||
// distance 400, 5 degrees of roll
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(400, cosf(DECIDEGREES_TO_RADIANS(50))), 398);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), 398);
|
|
||||||
// distance 400, 10 degrees of roll
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(400, cosf(DECIDEGREES_TO_RADIANS(100))), 393);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), 393);
|
|
||||||
// distance 400, 15 degrees of roll, this corresponds to HC-SR04 specified max detection angle
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(400, cosf(DECIDEGREES_TO_RADIANS(150))), 386);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), 386);
|
|
||||||
// distance 400, 20 degrees of roll
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(400, cosf(DECIDEGREES_TO_RADIANS(200))), 375);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), 375);
|
|
||||||
// distance 400, 22.4 degrees of roll, this corresponds to HC-SR04 effective max detection angle
|
|
||||||
EXPECT_EQ(sonarCalculateAltitude(400, cosf(DECIDEGREES_TO_RADIANS(224))), 369);
|
|
||||||
EXPECT_EQ(sonarGetLatestAltitude(), 369);
|
|
||||||
}
|
|
||||||
|
|
||||||
// STUBS
|
|
||||||
extern "C" {
|
|
||||||
void sensorsSet(uint32_t mask) {UNUSED(mask);}
|
|
||||||
}
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue