mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Merge remote-tracking branch 'origin/master' into sh_ahrs
This commit is contained in:
commit
918e658470
132 changed files with 393 additions and 816 deletions
|
@ -106,6 +106,7 @@ enum {
|
|||
#define EMERGENCY_ARMING_TIME_WINDOW_MS 10000
|
||||
#define EMERGENCY_ARMING_COUNTER_STEP_MS 1000
|
||||
#define EMERGENCY_ARMING_MIN_ARM_COUNT 10
|
||||
#define EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS 5000
|
||||
|
||||
timeDelta_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
|
||||
static timeUs_t flightTime = 0;
|
||||
|
@ -120,6 +121,7 @@ uint8_t motorControlEnable = false;
|
|||
static bool isRXDataNew;
|
||||
static disarmReason_t lastDisarmReason = DISARM_NONE;
|
||||
timeUs_t lastDisarmTimeUs = 0;
|
||||
timeMs_t emergRearmStabiliseTimeout = 0;
|
||||
|
||||
static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible
|
||||
static timeMs_t prearmActivationTime = 0;
|
||||
|
@ -315,11 +317,11 @@ static void updateArmingStatus(void)
|
|||
|
||||
/* CHECK: Do not allow arming if Servo AutoTrim is enabled */
|
||||
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) {
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
|
||||
}
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
|
||||
}
|
||||
else {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
|
||||
}
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
/* CHECK: Don't arm if the DShot beeper was used recently, as there is a minimum delay before sending the next DShot command */
|
||||
|
@ -435,6 +437,7 @@ void disarm(disarmReason_t disarmReason)
|
|||
lastDisarmReason = disarmReason;
|
||||
lastDisarmTimeUs = micros();
|
||||
DISABLE_ARMING_FLAG(ARMED);
|
||||
DISABLE_STATE(IN_FLIGHT_EMERG_REARM);
|
||||
|
||||
#ifdef USE_BLACKBOX
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
|
@ -505,14 +508,27 @@ bool emergencyArmingUpdate(bool armingSwitchIsOn, bool forceArm)
|
|||
return counter >= EMERGENCY_ARMING_MIN_ARM_COUNT;
|
||||
}
|
||||
|
||||
#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS)
|
||||
bool emergInflightRearmEnabled(void)
|
||||
{
|
||||
/* Emergency rearm allowed within 5s timeout period after disarm if craft still flying */
|
||||
timeMs_t currentTimeMs = millis();
|
||||
emergRearmStabiliseTimeout = 0;
|
||||
|
||||
void releaseSharedTelemetryPorts(void) {
|
||||
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||
while (sharedPort) {
|
||||
mspSerialReleasePortIfAllocated(sharedPort);
|
||||
sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||
if ((lastDisarmReason != DISARM_SWITCH && lastDisarmReason != DISARM_KILLSWITCH) ||
|
||||
(currentTimeMs > US2MS(lastDisarmTimeUs) + EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// allow emergency rearm if MR has vertical speed at least 1.5 sec after disarm indicating still flying
|
||||
bool mcDisarmVertVelCheck = STATE(MULTIROTOR) && (currentTimeMs > US2MS(lastDisarmTimeUs) + 1500) && fabsf(getEstimatedActualVelocity(Z)) > 100.0f;
|
||||
|
||||
if (isProbablyStillFlying() || mcDisarmVertVelCheck) {
|
||||
emergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise craft
|
||||
ENABLE_STATE(IN_FLIGHT_EMERG_REARM);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false; // craft doesn't appear to be flying, don't allow emergency rearm
|
||||
}
|
||||
|
||||
void tryArm(void)
|
||||
|
@ -538,9 +554,10 @@ void tryArm(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
if (!isArmingDisabled() || emergencyArmingIsEnabled() || LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) {
|
||||
if (emergInflightRearmEnabled() || !isArmingDisabled() || emergencyArmingIsEnabled() ||
|
||||
LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) {
|
||||
#else
|
||||
if (!isArmingDisabled() || emergencyArmingIsEnabled()) {
|
||||
if (emergInflightRearmEnabled() || !isArmingDisabled() || emergencyArmingIsEnabled()) {
|
||||
#endif
|
||||
// If nav_extra_arming_safety was bypassed we always
|
||||
// allow bypassing it even without the sticks set
|
||||
|
@ -558,11 +575,14 @@ void tryArm(void)
|
|||
ENABLE_ARMING_FLAG(WAS_EVER_ARMED);
|
||||
//It is required to inform the mixer that arming was executed and it has to switch to the FORWARD direction
|
||||
ENABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD);
|
||||
logicConditionReset();
|
||||
|
||||
if (!STATE(IN_FLIGHT_EMERG_REARM)) {
|
||||
resetLandingDetectorActiveState(); // reset landing detector after arming to avoid false detection before flight
|
||||
logicConditionReset();
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
programmingPidReset();
|
||||
programmingPidReset();
|
||||
#endif
|
||||
}
|
||||
|
||||
headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
|
||||
|
||||
|
@ -595,6 +615,16 @@ void tryArm(void)
|
|||
}
|
||||
}
|
||||
|
||||
#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS)
|
||||
|
||||
void releaseSharedTelemetryPorts(void) {
|
||||
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||
while (sharedPort) {
|
||||
mspSerialReleasePortIfAllocated(sharedPort);
|
||||
sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||
}
|
||||
}
|
||||
|
||||
void processRx(timeUs_t currentTimeUs)
|
||||
{
|
||||
// Calculate RPY channel data
|
||||
|
@ -645,9 +675,12 @@ void processRx(timeUs_t currentTimeUs)
|
|||
processRcAdjustments(CONST_CAST(controlRateConfig_t*, currentControlRateProfile), canUseRxData);
|
||||
}
|
||||
|
||||
// Angle mode forced on briefly after emergency inflight rearm to help stabilise attitude (currently limited to MR)
|
||||
bool emergRearmAngleEnforce = STATE(MULTIROTOR) && emergRearmStabiliseTimeout > US2MS(currentTimeUs);
|
||||
bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || emergRearmAngleEnforce;
|
||||
bool canUseHorizonMode = true;
|
||||
|
||||
if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeRequiresAngleMode() || navigationRequiresAngleMode()) && sensors(SENSOR_ACC)) {
|
||||
if (sensors(SENSOR_ACC) && (IS_RC_MODE_ACTIVE(BOXANGLE) || autoEnableAngle)) {
|
||||
// bumpless transfer to Level mode
|
||||
canUseHorizonMode = false;
|
||||
|
||||
|
@ -816,7 +849,6 @@ void processRx(timeUs_t currentTimeUs)
|
|||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
// Function for loop trigger
|
||||
|
@ -876,6 +908,10 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
processDelayedSave();
|
||||
}
|
||||
|
||||
if (armTime > 1 * USECS_PER_SEC) { // reset in flight emerg rearm flag 1 sec after arming once it's served its purpose
|
||||
DISABLE_STATE(IN_FLIGHT_EMERG_REARM);
|
||||
}
|
||||
|
||||
#if defined(SITL_BUILD)
|
||||
if (lockMainPID()) {
|
||||
#endif
|
||||
|
@ -925,15 +961,15 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
//Servos should be filtered or written only when mixer is using servos or special feaures are enabled
|
||||
|
||||
#ifdef USE_SIMULATOR
|
||||
if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) {
|
||||
if (isServoOutputEnabled()) {
|
||||
writeServos();
|
||||
}
|
||||
if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) {
|
||||
if (isServoOutputEnabled()) {
|
||||
writeServos();
|
||||
}
|
||||
|
||||
if (motorControlEnable) {
|
||||
writeMotors();
|
||||
}
|
||||
}
|
||||
if (motorControlEnable) {
|
||||
writeMotors();
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (isServoOutputEnabled()) {
|
||||
writeServos();
|
||||
|
|
|
@ -462,6 +462,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU16(dst, packSensorStatus());
|
||||
sbufWriteU16(dst, averageSystemLoadPercent);
|
||||
sbufWriteU8(dst, (getConfigBatteryProfile() << 4) | getConfigProfile());
|
||||
sbufWriteU8(dst, getConfigMixerProfile());
|
||||
sbufWriteU32(dst, armingFlags);
|
||||
sbufWriteData(dst, &mspBoxModeFlags, sizeof(mspBoxModeFlags));
|
||||
}
|
||||
|
@ -523,6 +524,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, -1);
|
||||
#endif
|
||||
}
|
||||
if(MAX_MIXER_PROFILE_COUNT==1) break;
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].targetChannel);
|
||||
sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].inputSource);
|
||||
sbufWriteU16(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].rate);
|
||||
sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].speed);
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].conditionId);
|
||||
#else
|
||||
sbufWriteU8(dst, -1);
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
case MSP2_INAV_LOGIC_CONDITIONS:
|
||||
|
@ -568,11 +581,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#endif
|
||||
case MSP2_COMMON_MOTOR_MIXER:
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
sbufWriteU16(dst, primaryMotorMixer(i)->throttle * 1000);
|
||||
sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->throttle + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->roll + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->pitch + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->yaw + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
}
|
||||
if (MAX_MIXER_PROFILE_COUNT==1) break;
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].throttle + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].roll + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].pitch + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].yaw + 2.0f, 0.0f, 4.0f) * 1000);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_MOTOR:
|
||||
|
@ -2121,7 +2141,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
case MSP2_COMMON_SET_MOTOR_MIXER:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
if ((dataSize == 9) && (tmp_u8 < MAX_SUPPORTED_MOTORS)) {
|
||||
primaryMotorMixerMutable(tmp_u8)->throttle = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 1.0f);
|
||||
primaryMotorMixerMutable(tmp_u8)->throttle = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f;
|
||||
primaryMotorMixerMutable(tmp_u8)->roll = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f;
|
||||
primaryMotorMixerMutable(tmp_u8)->pitch = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f;
|
||||
primaryMotorMixerMutable(tmp_u8)->yaw = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f;
|
||||
|
@ -3015,6 +3035,14 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP2_INAV_SELECT_MIXER_PROFILE:
|
||||
if (!ARMING_FLAG(ARMED) && sbufReadU8Safe(&tmp_u8, src)) {
|
||||
setConfigMixerProfileAndWriteEEPROM(tmp_u8);
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
|
||||
#ifdef USE_TEMPERATURE_SENSOR
|
||||
case MSP2_INAV_SET_TEMP_SENSOR_CONFIG:
|
||||
if (dataSize == sizeof(tempSensorConfig_t) * MAX_TEMP_SENSORS) {
|
||||
|
@ -3633,6 +3661,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
|
|||
}
|
||||
#endif
|
||||
ENABLE_ARMING_FLAG(SIMULATOR_MODE_HITL);
|
||||
ENABLE_STATE(ACCELEROMETER_CALIBRATED);
|
||||
LOG_DEBUG(SYSTEM, "Simulator enabled");
|
||||
}
|
||||
|
||||
|
|
|
@ -139,6 +139,7 @@ typedef enum {
|
|||
FW_HEADING_USE_YAW = (1 << 24),
|
||||
ANTI_WINDUP_DEACTIVATED = (1 << 25),
|
||||
LANDING_DETECTED = (1 << 26),
|
||||
IN_FLIGHT_EMERG_REARM = (1 << 27),
|
||||
} stateFlags_t;
|
||||
|
||||
#define DISABLE_STATE(mask) (stateFlags &= ~(mask))
|
||||
|
|
|
@ -35,7 +35,7 @@ int currentMixerProfileIndex;
|
|||
bool isMixerTransitionMixing;
|
||||
bool isMixerTransitionMixing_requested;
|
||||
mixerProfileAT_t mixerProfileAT;
|
||||
int nextProfileIndex;
|
||||
int nextMixerProfileIndex;
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1);
|
||||
|
||||
|
@ -81,7 +81,7 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance)
|
|||
void activateMixerConfig(){
|
||||
currentMixerProfileIndex = getConfigMixerProfile();
|
||||
currentMixerConfig = *mixerConfig();
|
||||
nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT;
|
||||
nextMixerProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT;
|
||||
}
|
||||
|
||||
void mixerConfigInit(void)
|
||||
|
@ -113,7 +113,7 @@ bool platformTypeConfigured(flyingPlatformType_e platformType)
|
|||
if (!isModeActivationConditionPresent(BOXMIXERPROFILE)){
|
||||
return false;
|
||||
}
|
||||
return mixerConfigByIndex(nextProfileIndex)->platformType == platformType;
|
||||
return mixerConfigByIndex(nextMixerProfileIndex)->platformType == platformType;
|
||||
}
|
||||
|
||||
bool checkMixerATRequired(mixerProfileATRequest_e required_action)
|
||||
|
@ -171,7 +171,7 @@ bool mixerATUpdateState(mixerProfileATRequest_e required_action)
|
|||
isMixerTransitionMixing_requested = true;
|
||||
if (millis() > mixerProfileAT.transitionTransEndTime){
|
||||
isMixerTransitionMixing_requested = false;
|
||||
outputProfileHotSwitch(nextProfileIndex);
|
||||
outputProfileHotSwitch(nextMixerProfileIndex);
|
||||
mixerProfileAT.phase = MIXERAT_PHASE_IDLE;
|
||||
reprocessState = true;
|
||||
//transition is done
|
||||
|
|
|
@ -54,6 +54,7 @@ bool mixerATUpdateState(mixerProfileATRequest_e required_action);
|
|||
|
||||
extern mixerConfig_t currentMixerConfig;
|
||||
extern int currentMixerProfileIndex;
|
||||
extern int nextMixerProfileIndex;
|
||||
extern bool isMixerTransitionMixing;
|
||||
#define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config))
|
||||
#define mixerConfigMutable() ((mixerConfig_t *) mixerConfig())
|
||||
|
|
|
@ -96,10 +96,31 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page)
|
|||
|
||||
case SYM_AH_DECORATION_DOWN:
|
||||
return BF_SYM_AH_DECORATION_DOWN;
|
||||
|
||||
case SYM_DIRECTION:
|
||||
return BF_SYM_DIRECTION;
|
||||
*/
|
||||
case SYM_DIRECTION:
|
||||
return BF_SYM_ARROW_NORTH;
|
||||
|
||||
case SYM_DIRECTION + 1: // NE pointing arrow
|
||||
return BF_SYM_ARROW_7;
|
||||
|
||||
case SYM_DIRECTION + 2: // E pointing arrow
|
||||
return BF_SYM_ARROW_EAST;
|
||||
|
||||
case SYM_DIRECTION + 3: // SE pointing arrow
|
||||
return BF_SYM_ARROW_3;
|
||||
|
||||
case SYM_DIRECTION + 4: // S pointing arrow
|
||||
return BF_SYM_ARROW_SOUTH;
|
||||
|
||||
case SYM_DIRECTION + 5: // SW pointing arrow
|
||||
return BF_SYM_ARROW_15;
|
||||
|
||||
case SYM_DIRECTION + 6: // W pointing arrow
|
||||
return BF_SYM_ARROW_WEST;
|
||||
|
||||
case SYM_DIRECTION + 7: // NW pointing arrow
|
||||
return BF_SYM_ARROW_11;
|
||||
|
||||
case SYM_VOLT:
|
||||
return BF_SYM_VOLT;
|
||||
|
||||
|
@ -187,13 +208,9 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page)
|
|||
case SYM_ALT_M:
|
||||
return BF_SYM_M;
|
||||
|
||||
/*
|
||||
case SYM_TRIP_DIST:
|
||||
return BF_SYM_TRIP_DIST;
|
||||
|
||||
case SYM_TOTAL:
|
||||
return BF_SYM_TOTAL;
|
||||
|
||||
return BF_SYM_TOTAL_DISTANCE;
|
||||
/*
|
||||
case SYM_ALT_KM:
|
||||
return BF_SYM_ALT_KM;
|
||||
|
||||
|
@ -226,20 +243,19 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page)
|
|||
/*
|
||||
case SYM_NM:
|
||||
return BF_SYM_NM;
|
||||
|
||||
*/
|
||||
case SYM_WIND_HORIZONTAL:
|
||||
return BF_SYM_WIND_HORIZONTAL;
|
||||
return 'W'; // W for wind
|
||||
|
||||
/*
|
||||
case SYM_WIND_VERTICAL:
|
||||
return BF_SYM_WIND_VERTICAL;
|
||||
|
||||
case SYM_3D_KT:
|
||||
return BF_SYM_3D_KT;
|
||||
|
||||
|
||||
case SYM_AIR:
|
||||
return BF_SYM_AIR;
|
||||
*/
|
||||
case SYM_AIR:
|
||||
return 'A'; // A for airspeed
|
||||
|
||||
case SYM_3D_KMH:
|
||||
return BF_SYM_KPH;
|
||||
|
@ -334,10 +350,12 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page)
|
|||
|
||||
case SYM_PITCH_DOWN:
|
||||
return BF_SYM_PITCH_DOWN;
|
||||
*/
|
||||
|
||||
case SYM_GFORCE:
|
||||
return BF_SYM_GFORCE;
|
||||
return 'G';
|
||||
|
||||
/*
|
||||
case SYM_GFORCE_X:
|
||||
return BF_SYM_GFORCE_X;
|
||||
|
||||
|
|
|
@ -1201,7 +1201,7 @@ int32_t osdGetAltitude(void)
|
|||
|
||||
static inline int32_t osdGetAltitudeMsl(void)
|
||||
{
|
||||
return getEstimatedActualPosition(Z)+GPS_home.alt;
|
||||
return getEstimatedActualPosition(Z) + posControl.gpsOrigin.alt;
|
||||
}
|
||||
|
||||
uint16_t osdGetRemainingGlideTime(void) {
|
||||
|
@ -1911,7 +1911,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0);
|
||||
break;
|
||||
|
||||
case OSD_ODOMETER:
|
||||
case OSD_ODOMETER:
|
||||
{
|
||||
displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_ODOMETER);
|
||||
uint32_t odometerDist = (uint32_t)(getTotalTravelDistance() / 100);
|
||||
|
@ -3955,7 +3955,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
|
|||
|
||||
/**
|
||||
* @brief Draws the INAV and/or pilot logos on the display
|
||||
*
|
||||
*
|
||||
* @param singular If true, only one logo will be drawn. If false, both logos will be drawn, separated by osdConfig()->inav_to_pilot_logo_spacing characters
|
||||
* @param row The row number to start drawing the logos. If not singular, both logos are drawn on the same rows.
|
||||
* @return uint8_t The row number after the logo(s).
|
||||
|
@ -4005,7 +4005,7 @@ uint8_t drawLogos(bool singular, uint8_t row) {
|
|||
} else {
|
||||
logo_x = logoColOffset + SYM_LOGO_WIDTH + logoSpacing;
|
||||
}
|
||||
|
||||
|
||||
for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) {
|
||||
for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) {
|
||||
displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++);
|
||||
|
@ -4129,7 +4129,7 @@ static void osdCompleteAsyncInitialization(void)
|
|||
|
||||
if (fontHasMetadata && metadata.charCount > 256) {
|
||||
hasExtendedFont = true;
|
||||
|
||||
|
||||
y = drawLogos(false, y);
|
||||
y++;
|
||||
} else if (!fontHasMetadata) {
|
||||
|
@ -4568,12 +4568,12 @@ static void osdShowHDArmScreen(void)
|
|||
|
||||
displayWrite(osdDisplayPort, col, armScreenRow, buf);
|
||||
displayWrite(osdDisplayPort, col + strlen(buf) + gap, armScreenRow++, buf2);
|
||||
|
||||
|
||||
int digits = osdConfig()->plus_code_digits;
|
||||
olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf));
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf);
|
||||
}
|
||||
|
||||
|
||||
#if defined (USE_SAFE_HOME)
|
||||
if (posControl.safehomeState.distance) { // safehome found during arming
|
||||
if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) {
|
||||
|
@ -4653,7 +4653,7 @@ static void osdShowSDArmScreen(void)
|
|||
uint8_t gpsStartCol = (osdDisplayPort->cols - (strlen(buf) + strlen(buf2) + 2)) / 2;
|
||||
displayWrite(osdDisplayPort, gpsStartCol, armScreenRow, buf);
|
||||
displayWrite(osdDisplayPort, gpsStartCol + strlen(buf) + 2, armScreenRow++, buf2);
|
||||
|
||||
|
||||
int digits = osdConfig()->plus_code_digits;
|
||||
olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf));
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf);
|
||||
|
@ -4806,10 +4806,14 @@ static void osdRefresh(timeUs_t currentTimeUs)
|
|||
statsDisplayed = false;
|
||||
osdResetStats();
|
||||
osdShowArmed();
|
||||
uint32_t delay = osdConfig()->arm_screen_display_time;
|
||||
uint16_t delay = osdConfig()->arm_screen_display_time;
|
||||
if (STATE(IN_FLIGHT_EMERG_REARM)) {
|
||||
delay = 500;
|
||||
}
|
||||
#if defined(USE_SAFE_HOME)
|
||||
if (posControl.safehomeState.distance)
|
||||
delay+= 3000;
|
||||
else if (posControl.safehomeState.distance) {
|
||||
delay += 3000;
|
||||
}
|
||||
#endif
|
||||
osdSetNextRefreshIn(delay);
|
||||
} else {
|
||||
|
|
|
@ -97,3 +97,5 @@
|
|||
|
||||
#define MSP2_INAV_EZ_TUNE 0x2070
|
||||
#define MSP2_INAV_EZ_TUNE_SET 0x2071
|
||||
|
||||
#define MSP2_INAV_SELECT_MIXER_PROFILE 0x2080
|
||||
|
|
|
@ -62,6 +62,7 @@
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "programming/global_variables.h"
|
||||
|
||||
|
@ -223,6 +224,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
static navWapointHeading_t wpHeadingControl;
|
||||
navigationPosControl_t posControl;
|
||||
navSystemStatus_t NAV_Status;
|
||||
static bool landingDetectorIsActive;
|
||||
|
||||
EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients;
|
||||
|
||||
|
@ -2660,11 +2662,15 @@ bool findNearestSafeHome(void)
|
|||
*-----------------------------------------------------------*/
|
||||
void updateHomePosition(void)
|
||||
{
|
||||
// Disarmed and have a valid position, constantly update home
|
||||
// Disarmed and have a valid position, constantly update home before first arm (depending on setting)
|
||||
// Update immediately after arming thereafter if reset on each arm (required to avoid home reset after emerg in flight rearm)
|
||||
static bool setHome = false;
|
||||
navSetWaypointFlags_t homeUpdateFlags = NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING;
|
||||
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
if (posControl.flags.estPosStatus >= EST_USABLE) {
|
||||
const navigationHomeFlags_t validHomeFlags = NAV_HOME_VALID_XY | NAV_HOME_VALID_Z;
|
||||
bool setHome = (posControl.rthState.homeFlags & validHomeFlags) != validHomeFlags;
|
||||
setHome = (posControl.rthState.homeFlags & validHomeFlags) != validHomeFlags;
|
||||
switch ((nav_reset_type_e)positionEstimationConfig()->reset_home_type) {
|
||||
case NAV_RESET_NEVER:
|
||||
break;
|
||||
|
@ -2675,24 +2681,16 @@ void updateHomePosition(void)
|
|||
setHome = true;
|
||||
break;
|
||||
}
|
||||
if (setHome) {
|
||||
#if defined(USE_SAFE_HOME)
|
||||
findNearestSafeHome();
|
||||
#endif
|
||||
setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity());
|
||||
// save the current location in case it is replaced by a safehome or HOME_RESET
|
||||
posControl.rthState.originalHomePosition = posControl.rthState.homePosition.pos;
|
||||
}
|
||||
}
|
||||
}
|
||||
else {
|
||||
static bool isHomeResetAllowed = false;
|
||||
|
||||
// If pilot so desires he may reset home position to current position
|
||||
if (IS_RC_MODE_ACTIVE(BOXHOMERESET)) {
|
||||
if (isHomeResetAllowed && !FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE) && (posControl.flags.estPosStatus >= EST_USABLE)) {
|
||||
const navSetWaypointFlags_t homeUpdateFlags = STATE(GPS_FIX_HOME) ? (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_HEADING) : (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
|
||||
setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, homeUpdateFlags, navigationActualStateHomeValidity());
|
||||
homeUpdateFlags = 0;
|
||||
homeUpdateFlags = STATE(GPS_FIX_HOME) ? (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_HEADING) : (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
|
||||
setHome = true;
|
||||
isHomeResetAllowed = false;
|
||||
}
|
||||
}
|
||||
|
@ -2707,6 +2705,22 @@ void updateHomePosition(void)
|
|||
posControl.homeDirection = calculateBearingToDestination(tmpHomePos);
|
||||
updateHomePositionCompatibility();
|
||||
}
|
||||
|
||||
setHome &= !STATE(IN_FLIGHT_EMERG_REARM); // prevent reset following emerg in flight rearm
|
||||
}
|
||||
|
||||
if (setHome && (!ARMING_FLAG(WAS_EVER_ARMED) || ARMING_FLAG(ARMED))) {
|
||||
#if defined(USE_SAFE_HOME)
|
||||
findNearestSafeHome();
|
||||
#endif
|
||||
setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, homeUpdateFlags, navigationActualStateHomeValidity());
|
||||
|
||||
if (ARMING_FLAG(ARMED) && positionEstimationConfig()->reset_altitude_type == NAV_RESET_ON_EACH_ARM) {
|
||||
posControl.rthState.homePosition.pos.z = 0; // force to 0 if reference altitude also reset every arm
|
||||
}
|
||||
// save the current location in case it is replaced by a safehome or HOME_RESET
|
||||
posControl.rthState.originalHomePosition = posControl.rthState.homePosition.pos;
|
||||
setHome = false;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2952,14 +2966,15 @@ void updateLandingStatus(timeMs_t currentTimeMs)
|
|||
}
|
||||
lastUpdateTimeMs = currentTimeMs;
|
||||
|
||||
static bool landingDetectorIsActive;
|
||||
|
||||
DEBUG_SET(DEBUG_LANDING, 0, landingDetectorIsActive);
|
||||
DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED));
|
||||
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
if (STATE(LANDING_DETECTED)) {
|
||||
landingDetectorIsActive = false;
|
||||
}
|
||||
resetLandingDetector();
|
||||
landingDetectorIsActive = false;
|
||||
|
||||
if (!IS_RC_MODE_ACTIVE(BOXARM)) {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED);
|
||||
}
|
||||
|
@ -2996,11 +3011,28 @@ void resetLandingDetector(void)
|
|||
posControl.flags.resetLandingDetector = true;
|
||||
}
|
||||
|
||||
void resetLandingDetectorActiveState(void)
|
||||
{
|
||||
landingDetectorIsActive = false;
|
||||
}
|
||||
|
||||
bool isFlightDetected(void)
|
||||
{
|
||||
return STATE(AIRPLANE) ? isFixedWingFlying() : isMulticopterFlying();
|
||||
}
|
||||
|
||||
bool isProbablyStillFlying(void)
|
||||
{
|
||||
bool inFlightSanityCheck;
|
||||
if (STATE(MULTIROTOR)) {
|
||||
inFlightSanityCheck = posControl.actualState.velXY > MC_LAND_CHECK_VEL_XY_MOVING || averageAbsGyroRates() > 4.0f;
|
||||
} else {
|
||||
inFlightSanityCheck = isGPSHeadingValid();
|
||||
}
|
||||
|
||||
return landingDetectorIsActive && inFlightSanityCheck;
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Z-position controller
|
||||
*-----------------------------------------------------------*/
|
||||
|
@ -3944,7 +3976,7 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
|
|||
canActivateWaypoint = false;
|
||||
|
||||
// Launch mode can be activated if feature FW_LAUNCH is enabled or BOX is turned on prior to arming (avoid switching to LAUNCH in flight)
|
||||
canActivateLaunchMode = isNavLaunchEnabled();
|
||||
canActivateLaunchMode = isNavLaunchEnabled() && (!sensors(SENSOR_GPS) || (sensors(SENSOR_GPS) && !isGPSHeadingValid()));
|
||||
}
|
||||
|
||||
return NAV_FSM_EVENT_SWITCH_TO_IDLE;
|
||||
|
|
|
@ -610,6 +610,8 @@ const char * fixedWingLaunchStateMessage(void);
|
|||
float calculateAverageSpeed(void);
|
||||
|
||||
void updateLandingStatus(timeMs_t currentTimeMs);
|
||||
bool isProbablyStillFlying(void);
|
||||
void resetLandingDetectorActiveState(void);
|
||||
|
||||
const navigationPIDControllers_t* getNavigationPIDControllers(void);
|
||||
|
||||
|
|
|
@ -695,7 +695,7 @@ bool isFixedWingFlying(void)
|
|||
bool velCondition = posControl.actualState.velXY > 250.0f || airspeed > 250.0f;
|
||||
bool launchCondition = isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING;
|
||||
|
||||
return (isImuHeadingValid() && throttleCondition && velCondition) || launchCondition;
|
||||
return (isGPSHeadingValid() && throttleCondition && velCondition) || launchCondition;
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
|
|
|
@ -54,6 +54,7 @@
|
|||
#include "sensors/opflow.h"
|
||||
|
||||
navigationPosEstimator_t posEstimator;
|
||||
static float initialBaroAltitudeOffset = 0.0f;
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 5);
|
||||
|
||||
|
@ -110,6 +111,25 @@ static bool updateTimer(navigationTimer_t * tim, timeUs_t interval, timeUs_t cur
|
|||
|
||||
static bool shouldResetReferenceAltitude(void)
|
||||
{
|
||||
/* Reference altitudes reset constantly when disarmed.
|
||||
* On arming ref altitudes saved as backup in case of emerg in flight rearm
|
||||
* If emerg in flight rearm active ref altitudes reset to backup values to avoid unwanted altitude reset */
|
||||
|
||||
static float backupInitialBaroAltitudeOffset = 0.0f;
|
||||
static int32_t backupGpsOriginAltitude = 0;
|
||||
static bool emergRearmResetCheck = false;
|
||||
|
||||
if (ARMING_FLAG(ARMED) && emergRearmResetCheck) {
|
||||
if (STATE(IN_FLIGHT_EMERG_REARM)) {
|
||||
initialBaroAltitudeOffset = backupInitialBaroAltitudeOffset;
|
||||
posControl.gpsOrigin.alt = backupGpsOriginAltitude;
|
||||
} else {
|
||||
backupInitialBaroAltitudeOffset = initialBaroAltitudeOffset;
|
||||
backupGpsOriginAltitude = posControl.gpsOrigin.alt;
|
||||
}
|
||||
}
|
||||
emergRearmResetCheck = !ARMING_FLAG(ARMED);
|
||||
|
||||
switch ((nav_reset_type_e)positionEstimationConfig()->reset_altitude_type) {
|
||||
case NAV_RESET_NEVER:
|
||||
return false;
|
||||
|
@ -305,7 +325,6 @@ void onNewGPSData(void)
|
|||
*/
|
||||
void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs)
|
||||
{
|
||||
static float initialBaroAltitudeOffset = 0.0f;
|
||||
float newBaroAlt = baroCalculateAltitude();
|
||||
|
||||
/* If we are required - keep altitude at zero */
|
||||
|
|
|
@ -86,14 +86,7 @@
|
|||
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
|
||||
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
|
|
@ -41,14 +41,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C2
|
||||
|
@ -139,4 +132,4 @@
|
|||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
|
@ -70,12 +70,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -46,13 +46,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_MPU9250
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -44,14 +44,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_MPU9250
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define AK8963_CS_PIN PC15
|
||||
#define AK8963_SPI_BUS BUS_SPI3
|
||||
|
|
|
@ -35,12 +35,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -35,12 +35,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -35,12 +35,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -98,13 +98,7 @@
|
|||
// Mag
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_MLX90393
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*** Onboard Flash ***/
|
||||
#define USE_SPI_DEVICE_3
|
||||
|
|
|
@ -60,13 +60,7 @@
|
|||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#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_ALL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
|
|
@ -101,12 +101,7 @@
|
|||
// Mag
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
/*** Onboard Flash ***/
|
||||
#define USE_SPI_DEVICE_3
|
||||
|
|
|
@ -67,13 +67,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -64,13 +64,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -116,13 +116,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_VCM5883
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -42,11 +42,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -74,12 +74,7 @@
|
|||
*/
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*
|
||||
* Barometer
|
||||
|
|
|
@ -134,11 +134,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -37,14 +37,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -112,14 +112,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -116,14 +116,12 @@
|
|||
#define MAX7456_CS_PIN PA15
|
||||
#endif
|
||||
|
||||
#if 0
|
||||
// I2C
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10 // SCL pad
|
||||
#define I2C2_SDA PB11 // SDA pad
|
||||
#define USE_I2C_PULLUP
|
||||
#endif
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C2
|
||||
|
@ -198,4 +196,4 @@
|
|||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
//#define USE_DSHOT
|
||||
//#define USE_ESC_SENSOR
|
||||
#define USE_ESCSERIAL
|
||||
#define USE_ESCSERIAL
|
||||
|
|
|
@ -70,12 +70,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -113,13 +113,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_AK8975
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -41,12 +41,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -42,12 +42,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C3
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C3
|
||||
|
||||
|
|
|
@ -82,13 +82,7 @@
|
|||
|
||||
#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_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -63,19 +63,12 @@
|
|||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_ALL
|
||||
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -41,12 +41,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -87,11 +87,7 @@
|
|||
#else
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#endif
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#if defined(OMNIBUSF4V6)
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -47,13 +47,7 @@
|
|||
// *************** Compass *****************************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_MPU9250
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
// *************** Temperature sensor *****************
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -58,13 +58,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -68,13 +68,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define USE_RANGEFINDER_HCSR04_I2C
|
||||
|
|
|
@ -70,12 +70,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
// *************** SPI OSD *****************************
|
||||
#define USE_MAX7456
|
||||
|
|
|
@ -143,12 +143,7 @@
|
|||
#define BARO_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC2
|
||||
|
|
|
@ -109,11 +109,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*** ADC ***/
|
||||
#define USE_ADC
|
||||
|
|
|
@ -104,11 +104,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*** ADC ***/
|
||||
#define USE_ADC
|
||||
|
|
|
@ -112,11 +112,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*** ADC ***/
|
||||
#define USE_ADC
|
||||
|
|
|
@ -124,11 +124,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -112,8 +112,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*** ADC ***/
|
||||
#define USE_ADC
|
||||
|
|
|
@ -83,13 +83,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_VCM5883
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
@ -162,4 +156,4 @@
|
|||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
|
@ -103,12 +103,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C3
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C3
|
||||
#define PITOT_I2C_BUS BUS_I2C3
|
||||
|
|
|
@ -53,12 +53,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -119,14 +119,7 @@
|
|||
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
|
|
|
@ -70,12 +70,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -67,12 +67,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -65,12 +65,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -65,12 +65,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -127,11 +127,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*** ADC ***/
|
||||
#define USE_ADC
|
||||
|
|
|
@ -134,11 +134,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*** ADC ***/
|
||||
#define USE_ADC
|
||||
|
|
|
@ -113,11 +113,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -137,11 +137,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -102,12 +102,7 @@
|
|||
// Mag
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
/*** Onboard Flash ***/
|
||||
#define USE_SPI_DEVICE_3
|
||||
|
|
|
@ -72,13 +72,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -97,13 +97,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_AK8975
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -59,12 +59,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -56,17 +56,12 @@
|
|||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C2
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_ALL
|
||||
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
|
||||
|
|
|
@ -56,13 +56,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -85,12 +85,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -62,12 +62,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -66,13 +66,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -59,12 +59,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -55,13 +55,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
@ -166,4 +160,4 @@
|
|||
|
||||
#define MAX_PWM_OUTPUT_PORTS 4
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
|
@ -62,12 +62,7 @@
|
|||
|
||||
# define USE_MAG
|
||||
# define MAG_I2C_BUS BUS_I2C1
|
||||
# define USE_MAG_HMC5883
|
||||
# define USE_MAG_QMC5883
|
||||
# define USE_MAG_MAG3110
|
||||
# define USE_MAG_IST8310
|
||||
# define USE_MAG_IST8308
|
||||
# define USE_MAG_LIS3MDL
|
||||
# define USE_MAG_ALL
|
||||
|
||||
# define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -135,13 +135,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_MLX90393
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -116,11 +116,7 @@
|
|||
*/
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
/*
|
||||
* ADC
|
||||
|
|
|
@ -132,13 +132,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_VCM5883
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -107,13 +107,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_VCM5883
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -36,12 +36,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -74,14 +74,7 @@
|
|||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
|
|
@ -83,14 +83,7 @@
|
|||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
@ -200,4 +193,4 @@
|
|||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC2
|
||||
#define PINIO2_PIN PC5
|
||||
#define PINIO2_PIN PC5
|
||||
|
|
|
@ -74,12 +74,7 @@
|
|||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
|
|
@ -86,11 +86,7 @@
|
|||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
@ -197,4 +193,4 @@
|
|||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC0 // VTX power switcher
|
||||
#define PINIO2_PIN PC2 // WiFi Switcher
|
||||
#define PINIO2_PIN PC2 // WiFi Switcher
|
||||
|
|
|
@ -55,12 +55,7 @@
|
|||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
@ -168,4 +163,4 @@
|
|||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC0
|
||||
#define PINIO2_PIN PC2
|
||||
#define PINIO2_PIN PC2
|
||||
|
|
|
@ -53,12 +53,7 @@
|
|||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
|
|
@ -124,13 +124,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_VCM5883
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
@ -238,4 +232,4 @@
|
|||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
|
@ -147,14 +147,7 @@
|
|||
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
|
|
|
@ -55,13 +55,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -68,13 +68,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define USE_RANGEFINDER_US42
|
||||
|
|
|
@ -92,12 +92,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -120,11 +120,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -103,13 +103,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_AK8975
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -88,13 +88,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_AK8975
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -56,12 +56,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
@ -152,4 +147,4 @@
|
|||
|
||||
#define MAX_PWM_OUTPUT_PORTS 7
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
|
@ -54,13 +54,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -68,13 +68,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
|
|
|
@ -87,12 +87,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -115,12 +115,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#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 USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -95,8 +95,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_ALL
|
||||
#define DEFAULT_I2C_BUS BUS_I2C2
|
||||
|
||||
// temperature sensors
|
||||
|
|
|
@ -93,8 +93,7 @@
|
|||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_ALL
|
||||
#define DEFAULT_I2C_BUS BUS_I2C2
|
||||
|
||||
// temperature sensors
|
||||
|
@ -196,4 +195,4 @@
|
|||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue