mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 16:25:26 +03:00
Merge remote-tracking branch 'origin/master' into dzikuvx-remove-f3
This commit is contained in:
commit
eb435c301b
31 changed files with 439 additions and 125 deletions
|
@ -37,7 +37,7 @@ else()
|
|||
include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake")
|
||||
endif()
|
||||
|
||||
project(INAV VERSION 5.0.0)
|
||||
project(INAV VERSION 6.0.0)
|
||||
|
||||
enable_language(ASM)
|
||||
|
||||
|
|
|
@ -2834,11 +2834,11 @@ Protocol that is used to send motor updates to ESCs. Possible values - STANDARD,
|
|||
|
||||
### motor_pwm_rate
|
||||
|
||||
Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000.
|
||||
Output frequency (in Hz) for motor pins. Applies only to brushed motors.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 400 | 50 | 32000 |
|
||||
| 16000 | 50 | 32000 |
|
||||
|
||||
---
|
||||
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#include "drivers/compass/compass.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
@ -287,6 +288,9 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
{"gyroADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroRaw", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW},
|
||||
{"gyroRaw", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW},
|
||||
{"gyroRaw", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW},
|
||||
{"accSmooth", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
|
||||
{"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
|
||||
{"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
|
||||
|
@ -458,6 +462,7 @@ typedef struct blackboxMainState_s {
|
|||
int16_t rcData[4];
|
||||
int16_t rcCommand[4];
|
||||
int16_t gyroADC[XYZ_AXIS_COUNT];
|
||||
int16_t gyroRaw[XYZ_AXIS_COUNT];
|
||||
int16_t accADC[XYZ_AXIS_COUNT];
|
||||
int16_t attitude[XYZ_AXIS_COUNT];
|
||||
int32_t debug[DEBUG32_VALUE_COUNT];
|
||||
|
@ -548,7 +553,7 @@ static struct {
|
|||
} xmitState;
|
||||
|
||||
// Cache for FLIGHT_LOG_FIELD_CONDITION_* test results:
|
||||
static uint32_t blackboxConditionCache;
|
||||
static uint64_t blackboxConditionCache;
|
||||
|
||||
STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION_LAST, too_many_flight_log_conditions);
|
||||
|
||||
|
@ -688,6 +693,9 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
case FLIGHT_LOG_FIELD_CONDITION_RC_DATA:
|
||||
return blackboxIncludeFlag(BLACKBOX_FEATURE_RC_DATA);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW:
|
||||
return blackboxIncludeFlag(BLACKBOX_FEATURE_GYRO_RAW);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
|
||||
return false;
|
||||
|
||||
|
@ -700,16 +708,20 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
static void blackboxBuildConditionCache(void)
|
||||
{
|
||||
blackboxConditionCache = 0;
|
||||
for (FlightLogFieldCondition cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
|
||||
for (uint8_t cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
|
||||
|
||||
const uint64_t position = ((uint64_t)1) << cond;
|
||||
|
||||
if (testBlackboxConditionUncached(cond)) {
|
||||
blackboxConditionCache |= 1 << cond;
|
||||
blackboxConditionCache |= position;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool testBlackboxCondition(FlightLogFieldCondition condition)
|
||||
{
|
||||
return (blackboxConditionCache & (1 << condition)) != 0;
|
||||
const uint64_t position = ((uint64_t)1) << condition;
|
||||
return (blackboxConditionCache & position) != 0;
|
||||
}
|
||||
|
||||
static void blackboxSetState(BlackboxState newState)
|
||||
|
@ -849,6 +861,10 @@ static void writeIntraframe(void)
|
|||
|
||||
blackboxWriteSigned16VBArray(blackboxCurrent->gyroADC, XYZ_AXIS_COUNT);
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW)) {
|
||||
blackboxWriteSigned16VBArray(blackboxCurrent->gyroRaw, XYZ_AXIS_COUNT);
|
||||
}
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
|
||||
blackboxWriteSigned16VBArray(blackboxCurrent->accADC, XYZ_AXIS_COUNT);
|
||||
}
|
||||
|
@ -1097,6 +1113,10 @@ static void writeInterframe(void)
|
|||
//Since gyros, accs and motors are noisy, base their predictions on the average of the history:
|
||||
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, gyroADC), XYZ_AXIS_COUNT);
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW)) {
|
||||
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, gyroRaw), XYZ_AXIS_COUNT);
|
||||
}
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
|
||||
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, accADC), XYZ_AXIS_COUNT);
|
||||
}
|
||||
|
@ -1471,6 +1491,7 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
blackboxCurrent->axisPID_F[i] = axisPID_F[i];
|
||||
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
|
||||
blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G);
|
||||
blackboxCurrent->gyroRaw[i] = lrintf(gyro.gyroRaw[i]);
|
||||
#ifdef USE_MAG
|
||||
blackboxCurrent->magADC[i] = mag.magADC[i];
|
||||
#endif
|
||||
|
@ -1811,7 +1832,7 @@ static bool blackboxWriteSysinfo(void)
|
|||
#endif
|
||||
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->motorPwmProtocol);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->motorPwmRate);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", getEscUpdateFrequency());
|
||||
BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
|
||||
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
|
||||
BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid());
|
||||
|
|
|
@ -31,6 +31,7 @@ typedef enum {
|
|||
BLACKBOX_FEATURE_RC_DATA = 1 << 6,
|
||||
BLACKBOX_FEATURE_RC_COMMAND = 1 << 7,
|
||||
BLACKBOX_FEATURE_MOTORS = 1 << 8,
|
||||
BLACKBOX_FEATURE_GYRO_RAW = 1 << 9,
|
||||
} blackboxFeatureMask_e;
|
||||
|
||||
|
||||
|
|
|
@ -60,6 +60,7 @@ typedef enum FlightLogFieldCondition {
|
|||
FLIGHT_LOG_FIELD_CONDITION_ATTITUDE,
|
||||
FLIGHT_LOG_FIELD_CONDITION_RC_DATA,
|
||||
FLIGHT_LOG_FIELD_CONDITION_RC_COMMAND,
|
||||
FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW,
|
||||
|
||||
FLIGHT_LOG_FIELD_CONDITION_NEVER,
|
||||
|
||||
|
|
|
@ -52,7 +52,6 @@ extern timeUs_t sectionTimes[2][4];
|
|||
|
||||
typedef enum {
|
||||
DEBUG_NONE,
|
||||
DEBUG_GYRO,
|
||||
DEBUG_AGL,
|
||||
DEBUG_FLOW_RAW,
|
||||
DEBUG_FLOW,
|
||||
|
|
|
@ -322,7 +322,7 @@ int fastA2I(const char *s)
|
|||
}
|
||||
|
||||
while ((digit = a2d(*s)) >= 0) {
|
||||
if (digit > 10)
|
||||
if (digit > 9)
|
||||
break;
|
||||
num = num * 10 + digit;
|
||||
s++;
|
||||
|
|
|
@ -16,6 +16,7 @@
|
|||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "sensors/barometer.h" // for baroSensor_e enum
|
||||
|
||||
bool ms5607Detect(baroDev_t *baro);
|
||||
|
|
|
@ -464,26 +464,56 @@ void pwmMotorPreconfigure(void)
|
|||
case PWM_TYPE_DSHOT600:
|
||||
case PWM_TYPE_DSHOT300:
|
||||
case PWM_TYPE_DSHOT150:
|
||||
motorConfigDigitalUpdateInterval(motorConfig()->motorPwmRate);
|
||||
motorConfigDigitalUpdateInterval(getEscUpdateFrequency());
|
||||
motorWritePtr = pwmWriteDigital;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function return the PWM frequency based on ESC protocol. We allow customer rates only for Brushed motors
|
||||
*/
|
||||
uint32_t getEscUpdateFrequency(void) {
|
||||
switch (initMotorProtocol) {
|
||||
case PWM_TYPE_BRUSHED:
|
||||
return motorConfig()->motorPwmRate;
|
||||
|
||||
case PWM_TYPE_STANDARD:
|
||||
return 400;
|
||||
|
||||
case PWM_TYPE_MULTISHOT:
|
||||
return 2000;
|
||||
|
||||
case PWM_TYPE_DSHOT150:
|
||||
return 4000;
|
||||
|
||||
case PWM_TYPE_DSHOT300:
|
||||
return 8000;
|
||||
|
||||
case PWM_TYPE_DSHOT600:
|
||||
return 16000;
|
||||
|
||||
case PWM_TYPE_ONESHOT125:
|
||||
default:
|
||||
return 1000;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bool enableOutput)
|
||||
{
|
||||
switch (initMotorProtocol) {
|
||||
case PWM_TYPE_BRUSHED:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 0.0f, 0.0f, motorConfig()->motorPwmRate, enableOutput);
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 0.0f, 0.0f, getEscUpdateFrequency(), enableOutput);
|
||||
break;
|
||||
|
||||
case PWM_TYPE_ONESHOT125:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorConfig()->motorPwmRate, enableOutput);
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, getEscUpdateFrequency(), enableOutput);
|
||||
break;
|
||||
|
||||
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, getEscUpdateFrequency(), enableOutput);
|
||||
break;
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
|
@ -495,7 +525,7 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bo
|
|||
#endif
|
||||
|
||||
case PWM_TYPE_STANDARD:
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, motorConfig()->motorPwmRate, enableOutput);
|
||||
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, getEscUpdateFrequency(), enableOutput);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
|
|
@ -56,3 +56,5 @@ void beeperPwmInit(ioTag_t tag, uint16_t frequency);
|
|||
|
||||
void sendDShotCommand(dshotCommands_e cmd);
|
||||
void initDShotCommands(void);
|
||||
|
||||
uint32_t getEscUpdateFrequency(void);
|
|
@ -38,8 +38,6 @@ typedef enum portOptions_t {
|
|||
SERIAL_PARITY_EVEN = 1 << 2,
|
||||
SERIAL_UNIDIR = 0 << 3,
|
||||
SERIAL_BIDIR = 1 << 3,
|
||||
SERIAL_LONGSTOP = 0 << 4,
|
||||
SERIAL_SHORTSTOP = 1 << 4,
|
||||
|
||||
/*
|
||||
* Note on SERIAL_BIDIR_PP
|
||||
|
@ -52,6 +50,9 @@ typedef enum portOptions_t {
|
|||
SERIAL_BIDIR_PP = 1 << 4,
|
||||
SERIAL_BIDIR_NOPULL = 1 << 5, // disable pulls in BIDIR RX mode
|
||||
SERIAL_BIDIR_UP = 0 << 5, // enable pullup in BIDIR mode
|
||||
|
||||
SERIAL_LONGSTOP = 0 << 6,
|
||||
SERIAL_SHORTSTOP = 1 << 6,
|
||||
} portOptions_t;
|
||||
|
||||
typedef void (*serialReceiveCallbackPtr)(uint16_t data, void *rxCallbackData); // used by serial drivers to return frames to app
|
||||
|
|
|
@ -164,7 +164,7 @@ static const char * const featureNames[] = {
|
|||
|
||||
#ifdef USE_BLACKBOX
|
||||
static const char * const blackboxIncludeFlagNames[] = {
|
||||
"NAV_ACC", "NAV_POS", "NAV_PID", "MAG", "ACC", "ATTI", "RC_DATA", "RC_COMMAND", "MOTORS", NULL
|
||||
"NAV_ACC", "NAV_POS", "NAV_PID", "MAG", "ACC", "ATTI", "RC_DATA", "RC_COMMAND", "MOTORS", "GYRO_RAW", NULL
|
||||
};
|
||||
#endif
|
||||
|
||||
|
|
|
@ -107,7 +107,7 @@ PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
|||
.enabledFeatures = DEFAULT_FEATURES | COMMON_DEFAULT_FEATURES
|
||||
);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 5);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 6);
|
||||
|
||||
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||
.current_profile_index = 0,
|
||||
|
@ -237,39 +237,7 @@ void validateAndFixConfig(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef BRUSHED_MOTORS
|
||||
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000);
|
||||
#else
|
||||
switch (motorConfig()->motorPwmProtocol) {
|
||||
default:
|
||||
case PWM_TYPE_STANDARD: // Limited to 490 Hz
|
||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 490);
|
||||
break;
|
||||
case PWM_TYPE_ONESHOT125: // Limited to 3900 Hz
|
||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 3900);
|
||||
break;
|
||||
case PWM_TYPE_MULTISHOT: // 2-16 kHz
|
||||
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 16000);
|
||||
break;
|
||||
case PWM_TYPE_BRUSHED: // 500Hz - 32kHz
|
||||
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000);
|
||||
break;
|
||||
#ifdef USE_DSHOT
|
||||
// One DSHOT packet takes 16 bits x 19 ticks + 2uS = 304 timer ticks + 2uS
|
||||
case PWM_TYPE_DSHOT150:
|
||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 4000);
|
||||
break;
|
||||
case PWM_TYPE_DSHOT300:
|
||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 8000);
|
||||
break;
|
||||
// Although DSHOT 600+ support >16kHz update rate it's not practical because of increased CPU load
|
||||
// It's more reasonable to use slower-speed DSHOT at higher rate for better reliability
|
||||
case PWM_TYPE_DSHOT600:
|
||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 16000);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// Call target-specific validation function
|
||||
validateAndFixTargetConfig();
|
||||
|
|
|
@ -265,7 +265,26 @@ static void updateArmingStatus(void)
|
|||
#endif
|
||||
|
||||
/* CHECK: */
|
||||
if (sensors(SENSOR_ACC) && !STATE(ACCELEROMETER_CALIBRATED)) {
|
||||
if (
|
||||
sensors(SENSOR_ACC) &&
|
||||
!STATE(ACCELEROMETER_CALIBRATED) &&
|
||||
// Require ACC calibration only if any of the setting might require it
|
||||
(
|
||||
isModeActivationConditionPresent(BOXNAVPOSHOLD) ||
|
||||
isModeActivationConditionPresent(BOXNAVRTH) ||
|
||||
isModeActivationConditionPresent(BOXNAVWP) ||
|
||||
isModeActivationConditionPresent(BOXANGLE) ||
|
||||
isModeActivationConditionPresent(BOXHORIZON) ||
|
||||
isModeActivationConditionPresent(BOXNAVALTHOLD) ||
|
||||
isModeActivationConditionPresent(BOXHEADINGHOLD) ||
|
||||
isModeActivationConditionPresent(BOXNAVLAUNCH) ||
|
||||
isModeActivationConditionPresent(BOXTURNASSIST) ||
|
||||
isModeActivationConditionPresent(BOXNAVCOURSEHOLD) ||
|
||||
isModeActivationConditionPresent(BOXSOARING) ||
|
||||
failsafeConfig()->failsafe_procedure != FAILSAFE_PROCEDURE_DROP_IT
|
||||
|
||||
)
|
||||
) {
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED);
|
||||
}
|
||||
else {
|
||||
|
|
|
@ -19,7 +19,7 @@ tables:
|
|||
values: ["NONE", "CXOF", "MSP", "FAKE"]
|
||||
enum: opticalFlowSensor_e
|
||||
- name: baro_hardware
|
||||
values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "MSP", "FAKE"]
|
||||
values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "B2SMPB", "MSP", "FAKE"]
|
||||
enum: baroSensor_e
|
||||
- name: pitot_hardware
|
||||
values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
|
||||
|
@ -91,14 +91,12 @@ tables:
|
|||
- name: i2c_speed
|
||||
values: ["400KHZ", "800KHZ", "100KHZ", "200KHZ"]
|
||||
- name: debug_modes
|
||||
values: ["NONE", "GYRO", "AGL", "FLOW_RAW",
|
||||
values: ["NONE", "AGL", "FLOW_RAW",
|
||||
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
|
||||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
|
||||
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
|
||||
"IRLOCK", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "IMU2", "ALTITUDE",
|
||||
"SMITH_PREDICTOR", "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING"]
|
||||
- name: async_mode
|
||||
values: ["NONE", "GYRO", "ALL"]
|
||||
- name: aux_operator
|
||||
values: ["OR", "AND"]
|
||||
enum: modeActivationOperator_e
|
||||
|
@ -848,8 +846,8 @@ groups:
|
|||
min: 0
|
||||
max: PWM_RANGE_MAX
|
||||
- name: motor_pwm_rate
|
||||
description: "Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000."
|
||||
default_value: 400
|
||||
description: "Output frequency (in Hz) for motor pins. Applies only to brushed motors. "
|
||||
default_value: 16000
|
||||
field: motorPwmRate
|
||||
min: 50
|
||||
max: 32000
|
||||
|
|
|
@ -147,7 +147,8 @@ static float computeParabolaMean(gyroAnalyseState_t *state, uint8_t peakBinIndex
|
|||
// Estimate true peak position aka. preciseBin (fit parabola y(x) over y0, y1 and y2, solve dy/dx=0 for x)
|
||||
const float denom = 2.0f * (y0 - 2 * y1 + y2);
|
||||
if (denom != 0.0f) {
|
||||
preciseBin += (y0 - y2) / denom;
|
||||
//Cap precise bin to prevent off values if parabola is not fitted correctly
|
||||
preciseBin += constrainf((y0 - y2) / denom, -0.5f, 0.5f);
|
||||
}
|
||||
|
||||
return preciseBin;
|
||||
|
|
|
@ -67,6 +67,14 @@
|
|||
#define UBX_VALID_GPS_TIME(valid) (valid & 1 << 1)
|
||||
#define UBX_VALID_GPS_DATE_TIME(valid) (UBX_VALID_GPS_DATE(valid) && UBX_VALID_GPS_TIME(valid))
|
||||
|
||||
#define UBX_HW_VERSION_UNKNOWN 0
|
||||
#define UBX_HW_VERSION_UBLOX5 500
|
||||
#define UBX_HW_VERSION_UBLOX6 600
|
||||
#define UBX_HW_VERSION_UBLOX7 700
|
||||
#define UBX_HW_VERSION_UBLOX8 800
|
||||
#define UBX_HW_VERSION_UBLOX9 900
|
||||
#define UBX_HW_VERSION_UBLOX10 1000
|
||||
|
||||
// SBAS_AUTO, SBAS_EGNOS, SBAS_WAAS, SBAS_MSAS, SBAS_GAGAN, SBAS_NONE
|
||||
// note PRNs last upadted 2020-12-18
|
||||
|
||||
|
@ -557,11 +565,45 @@ static void configureSBAS(void)
|
|||
sendConfigMessageUBLOX();
|
||||
}
|
||||
|
||||
static uint32_t gpsDecodeHardwareVersion(const char * szBuf, unsigned nBufSize)
|
||||
{
|
||||
// ublox_5 hwVersion 00040005
|
||||
if (strncmp(szBuf, "00040005", nBufSize) == 0) {
|
||||
return UBX_HW_VERSION_UBLOX5;
|
||||
}
|
||||
|
||||
// ublox_6 hwVersion 00040007
|
||||
if (strncmp(szBuf, "00040007", nBufSize) == 0) {
|
||||
return UBX_HW_VERSION_UBLOX6;
|
||||
}
|
||||
|
||||
// ublox_7 hwVersion 00070000
|
||||
if (strncmp(szBuf, "00070000", nBufSize) == 0) {
|
||||
return UBX_HW_VERSION_UBLOX7;
|
||||
}
|
||||
|
||||
// ublox_M8 hwVersion 00080000
|
||||
if (strncmp(szBuf, "00080000", nBufSize) == 0) {
|
||||
return UBX_HW_VERSION_UBLOX8;
|
||||
}
|
||||
|
||||
// ublox_M9 hwVersion 00190000
|
||||
if (strncmp(szBuf, "00190000", nBufSize) == 0) {
|
||||
return UBX_HW_VERSION_UBLOX9;
|
||||
}
|
||||
|
||||
// ublox_M10 hwVersion 000A0000
|
||||
if (strncmp(szBuf, "000A0000", nBufSize) == 0) {
|
||||
return UBX_HW_VERSION_UBLOX10;
|
||||
}
|
||||
|
||||
return UBX_HW_VERSION_UNKNOWN;
|
||||
}
|
||||
|
||||
static bool gpsParceFrameUBLOX(void)
|
||||
{
|
||||
switch (_msg_id) {
|
||||
case MSG_POSLLH:
|
||||
//i2c_dataset.time = _buffer.posllh.time;
|
||||
gpsSol.llh.lon = _buffer.posllh.longitude;
|
||||
gpsSol.llh.lat = _buffer.posllh.latitude;
|
||||
gpsSol.llh.alt = _buffer.posllh.altitude_msl / 10; //alt in cm
|
||||
|
@ -647,11 +689,8 @@ static bool gpsParceFrameUBLOX(void)
|
|||
break;
|
||||
case MSG_VER:
|
||||
if (_class == CLASS_MON) {
|
||||
//uint32_t swver = _buffer.ver.swVersion;
|
||||
// EXT CORE 3.01 (107900)
|
||||
// 01234567890123456789012
|
||||
gpsState.hwVersion = fastA2I(_buffer.ver.hwVersion);
|
||||
if ((gpsState.hwVersion >= 80000) && (_buffer.ver.swVersion[9] > '2')) {
|
||||
gpsState.hwVersion = gpsDecodeHardwareVersion(_buffer.ver.hwVersion, sizeof(_buffer.ver.hwVersion));
|
||||
if ((gpsState.hwVersion >= UBX_HW_VERSION_UBLOX8) && (_buffer.ver.swVersion[9] > '2')) {
|
||||
// check extensions;
|
||||
// after hw + sw vers; each is 30 bytes
|
||||
for(int j = 40; j < _payload_length; j += 30) {
|
||||
|
@ -823,9 +862,8 @@ STATIC_PROTOTHREAD(gpsConfigure)
|
|||
// Configure UBX binary messages
|
||||
gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT);
|
||||
|
||||
// u-Blox 9
|
||||
// M9N does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence
|
||||
if (gpsState.hwVersion >= 190000) {
|
||||
// M9N & M10 does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence
|
||||
if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX9) {
|
||||
configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
|
@ -853,9 +891,41 @@ STATIC_PROTOTHREAD(gpsConfigure)
|
|||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
}
|
||||
else {
|
||||
// u-Blox 6/7/8
|
||||
// u-Blox 6 doesn't support PVT, use legacy config
|
||||
if ((gpsState.gpsConfig->provider == GPS_UBLOX) || (gpsState.hwVersion < 70000)) {
|
||||
// u-Blox 5/6/7/8 or unknown
|
||||
// u-Blox 7-8 support PVT
|
||||
if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7) {
|
||||
configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_SOL, 1);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_VELNED, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_PVT, 1);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) {
|
||||
configureRATE(100); // 10Hz
|
||||
}
|
||||
else {
|
||||
configureRATE(200); // 5Hz
|
||||
}
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
}
|
||||
// u-Blox 5/6 doesn't support PVT, use legacy config
|
||||
// UNKNOWN also falls here, use as a last resort
|
||||
else {
|
||||
configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 1);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
|
@ -882,37 +952,6 @@ STATIC_PROTOTHREAD(gpsConfigure)
|
|||
configureRATE(200);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
}
|
||||
// u-Blox 7-8 support PVT
|
||||
else {
|
||||
configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_SOL, 1);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_VELNED, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_PVT, 1);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0);
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
|
||||
if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= 70000)) {
|
||||
configureRATE(100); // 10Hz
|
||||
}
|
||||
else {
|
||||
configureRATE(200); // 5Hz
|
||||
}
|
||||
ptWait(_ack_state == UBX_ACK_GOT_ACK);
|
||||
}
|
||||
}
|
||||
|
||||
// Configure SBAS
|
||||
|
@ -994,14 +1033,14 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread)
|
|||
gpsSetProtocolTimeout(MAX(GPS_TIMEOUT, ((GPS_VERSION_RETRY_TIMES + 3) * GPS_CFG_CMD_TIMEOUT_MS)));
|
||||
|
||||
// Attempt to detect GPS hw version
|
||||
gpsState.hwVersion = 0;
|
||||
gpsState.hwVersion = UBX_HW_VERSION_UNKNOWN;
|
||||
gpsState.autoConfigStep = 0;
|
||||
|
||||
do {
|
||||
pollVersion();
|
||||
gpsState.autoConfigStep++;
|
||||
ptWaitTimeout((gpsState.hwVersion != 0), GPS_CFG_CMD_TIMEOUT_MS);
|
||||
} while(gpsState.autoConfigStep < GPS_VERSION_RETRY_TIMES && gpsState.hwVersion == 0);
|
||||
ptWaitTimeout((gpsState.hwVersion != UBX_HW_VERSION_UNKNOWN), GPS_CFG_CMD_TIMEOUT_MS);
|
||||
} while(gpsState.autoConfigStep < GPS_VERSION_RETRY_TIMES && gpsState.hwVersion == UBX_HW_VERSION_UNKNOWN);
|
||||
|
||||
// Configure GPS
|
||||
ptSpawn(gpsConfigure);
|
||||
|
|
|
@ -1209,7 +1209,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_INITIALIZE(navigati
|
|||
|
||||
if (STATE(FIXED_WING_LEGACY)) {
|
||||
// Airplane - climbout before heading home
|
||||
if (navConfig()->general.flags.rth_climb_first == ON_FW_SPIRAL) {
|
||||
if (navConfig()->general.flags.rth_climb_first == RTH_CLIMB_ON_FW_SPIRAL) {
|
||||
// Spiral climb centered at xy of RTH activation
|
||||
calculateInitialHoldPosition(&targetHoldPos);
|
||||
} else {
|
||||
|
@ -1258,7 +1258,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_CLIMB_TO_SAFE_ALT(n
|
|||
const float rthAltitudeMargin = MAX(FW_RTH_CLIMB_MARGIN_MIN_CM, (rthClimbMarginPercent/100.0) * fabsf(posControl.rthState.rthInitialAltitude - posControl.rthState.homePosition.pos.z));
|
||||
|
||||
// If we reached desired initial RTH altitude or we don't want to climb first
|
||||
if (((navGetCurrentActualPositionAndVelocity()->pos.z - posControl.rthState.rthInitialAltitude) > -rthAltitudeMargin) || (navConfig()->general.flags.rth_climb_first == OFF) || rthAltControlStickOverrideCheck(ROLL) || rthClimbStageActiveAndComplete()) {
|
||||
if (((navGetCurrentActualPositionAndVelocity()->pos.z - posControl.rthState.rthInitialAltitude) > -rthAltitudeMargin) || (navConfig()->general.flags.rth_climb_first == RTH_CLIMB_OFF) || rthAltControlStickOverrideCheck(ROLL) || rthClimbStageActiveAndComplete()) {
|
||||
|
||||
// Delayed initialization for RTH sanity check on airplanes - allow to finish climb first as it can take some distance
|
||||
if (STATE(FIXED_WING_LEGACY)) {
|
||||
|
@ -1289,7 +1289,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_CLIMB_TO_SAFE_ALT(n
|
|||
|
||||
// Climb to safe altitude and turn to correct direction
|
||||
if (STATE(FIXED_WING_LEGACY)) {
|
||||
if (navConfig()->general.flags.rth_climb_first == ON_FW_SPIRAL) {
|
||||
if (navConfig()->general.flags.rth_climb_first == RTH_CLIMB_ON_FW_SPIRAL) {
|
||||
float altitudeChangeDirection = (tmpHomePos->z += FW_RTH_CLIMB_OVERSHOOT_CM) > navGetCurrentActualPositionAndVelocity()->pos.z ? 1 : -1;
|
||||
updateClimbRateToAltitudeController(altitudeChangeDirection * navConfig()->general.max_auto_climb_rate, ROC_TO_ALT_NORMAL);
|
||||
} else {
|
||||
|
|
|
@ -139,9 +139,9 @@ typedef enum {
|
|||
} navOverridesMotorStop_e;
|
||||
|
||||
typedef enum {
|
||||
OFF,
|
||||
ON,
|
||||
ON_FW_SPIRAL,
|
||||
RTH_CLIMB_OFF,
|
||||
RTH_CLIMB_ON,
|
||||
RTH_CLIMB_ON_FW_SPIRAL,
|
||||
} navRTHClimbFirst_e;
|
||||
|
||||
typedef enum { // keep aligned with fixedWingLaunchState_t
|
||||
|
|
|
@ -505,7 +505,8 @@ void FAST_CODE NOINLINE gyroUpdate()
|
|||
// At this point gyro.gyroADCf contains unfiltered gyro value [deg/s]
|
||||
float gyroADCf = gyro.gyroADCf[axis];
|
||||
|
||||
DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf));
|
||||
// Set raw gyro for blackbox purposes
|
||||
gyro.gyroRaw[axis] = gyroADCf;
|
||||
|
||||
/*
|
||||
* First gyro LPF is the only filter applied with the full gyro sampling speed
|
||||
|
|
|
@ -48,6 +48,7 @@ typedef struct gyro_s {
|
|||
bool initialized;
|
||||
uint32_t targetLooptime;
|
||||
float gyroADCf[XYZ_AXIS_COUNT];
|
||||
float gyroRaw[XYZ_AXIS_COUNT];
|
||||
} gyro_t;
|
||||
|
||||
extern gyro_t gyro;
|
||||
|
|
|
@ -36,6 +36,5 @@ void targetConfiguration(void)
|
|||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT;
|
||||
motorConfigMutable()->motorPwmRate = 4000;
|
||||
motorConfigMutable()->maxthrottle = 1950;
|
||||
}
|
||||
|
|
|
@ -36,6 +36,5 @@ void targetConfiguration(void)
|
|||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT;
|
||||
motorConfigMutable()->motorPwmRate = 4000;
|
||||
motorConfigMutable()->maxthrottle = 1950;
|
||||
}
|
||||
|
|
|
@ -73,7 +73,6 @@ void validateAndFixTargetConfig(void)
|
|||
if (mixerConfig()->platformType != PLATFORM_MULTIROTOR && mixerConfig()->platformType != PLATFORM_TRICOPTER) {
|
||||
if (motorConfig()->motorPwmProtocol >= PWM_TYPE_DSHOT150) {
|
||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_STANDARD;
|
||||
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 490);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -35,15 +35,21 @@
|
|||
#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_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW180_DEG_FLIP
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_CS_PIN PA4
|
||||
//#define MPU6000_EXTI_PIN GYRO_INT_EXTI
|
||||
|
||||
#define USE_IMU_BMI270
|
||||
#define IMU_BMI270_ALIGN CW180_DEG_FLIP
|
||||
#define BMI270_SPI_BUS BUS_SPI1
|
||||
#define BMI270_CS_PIN PA4
|
||||
#define BMI270_EXTI_PIN GYRO_INT_EXTI
|
||||
|
||||
// *************** M25P256 flash ********************
|
||||
#define USE_FLASHFS
|
||||
|
|
1
src/main/target/SKYSTARSF722HD/CMakeLists.txt
Normal file
1
src/main/target/SKYSTARSF722HD/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32f722xe(SKYSTARSF722HD)
|
29
src/main/target/SKYSTARSF722HD/config.c
Normal file
29
src/main/target/SKYSTARSF722HD/config.c
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* 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>
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_DJI_HD_OSD;
|
||||
}
|
35
src/main/target/SKYSTARSF722HD/target.c
Normal file
35
src/main/target/SKYSTARSF722HD/target.c
Normal file
|
@ -0,0 +1,35 @@
|
|||
/*
|
||||
* 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 <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_PPM, 0, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // TIM3_CH3 / TIM8_CH3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // TIM3_CH4 / TIM8_CH4
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // TIM4_CH1
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // TIM4_CH2
|
||||
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0),
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
163
src/main/target/SKYSTARSF722HD/target.h
Normal file
163
src/main/target/SKYSTARSF722HD/target.h
Normal file
|
@ -0,0 +1,163 @@
|
|||
/*
|
||||
* 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 TARGET_BOARD_IDENTIFIER "SS7D"
|
||||
|
||||
#define USBD_PRODUCT_STRING "SkystarsF722HD"
|
||||
|
||||
#define LED0 PC14 // green
|
||||
#define LED1 PC15 // blue
|
||||
|
||||
#define BEEPER PB2
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** Gyro & Acc **********************
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define BMI270_CS_PIN PA4
|
||||
#define BMI270_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_EXTI
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_IMU_BMI270
|
||||
#define IMU_BMI270_ALIGN CW90_DEG_FLIP
|
||||
|
||||
// *************** M25P256 flash ********************
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PA15
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
// *************** OSD & baro ***********************
|
||||
#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
|
||||
|
||||
#define USE_BARO
|
||||
#define USE_BARO_BMP280
|
||||
#define BMP280_SPI_BUS BUS_SPI2
|
||||
#define BMP280_CS_PIN PB1
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#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
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
|
||||
// *************** I2C ****************************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
#define DEFAULT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define BNO055_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define USE_RANGEFINDER_MSP
|
||||
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC1
|
||||
#define ADC_CHANNEL_2_PIN PC2
|
||||
#define ADC_CHANNEL_3_PIN PC3
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_2
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY )
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PB3
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 4
|
|
@ -26,13 +26,13 @@
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP(1,2)
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 UP(2,1)
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP(1,2)
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP(2,1)
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP(2,1)
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP(2,1)
|
||||
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 UP(1,7)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 UP(2,5)
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S5 UP(1,7)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S6 UP(2,5)
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,7)!S5 UP(2,6)
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED D(1,0) UP(2,6)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue