Changed defines for GYRO/ACC/MAG/BARO/GPS/SONAR/OSD/BLACKBOX/CMS to conform to the USE_ convention.
This commit is contained in:
parent
62c5711ce7
commit
a8d34dabb0
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
|
|
||||||
#include "blackbox.h"
|
#include "blackbox.h"
|
||||||
#include "blackbox_encoding.h"
|
#include "blackbox_encoding.h"
|
||||||
|
@ -187,15 +187,15 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
||||||
{"vbatLatest", -1, UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT},
|
{"vbatLatest", -1, UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT},
|
||||||
{"amperageLatest",-1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC},
|
{"amperageLatest",-1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC},
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
{"magADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
|
{"magADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
|
||||||
{"magADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
|
{"magADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
|
||||||
{"magADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
|
{"magADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
|
||||||
#endif
|
#endif
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
{"BaroAlt", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_BARO},
|
{"BaroAlt", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_BARO},
|
||||||
#endif
|
#endif
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
{"sonarRaw", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_SONAR},
|
{"sonarRaw", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_SONAR},
|
||||||
#endif
|
#endif
|
||||||
{"rssi", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_RSSI},
|
{"rssi", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_RSSI},
|
||||||
|
@ -226,7 +226,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
||||||
{"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)}
|
{"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)}
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
// GPS position/vel frame
|
// GPS position/vel frame
|
||||||
static const blackboxConditionalFieldDefinition_t blackboxGpsGFields[] = {
|
static const blackboxConditionalFieldDefinition_t blackboxGpsGFields[] = {
|
||||||
{"time", -1, UNSIGNED, PREDICT(LAST_MAIN_FRAME_TIME), ENCODING(UNSIGNED_VB), CONDITION(NOT_LOGGING_EVERY_FRAME)},
|
{"time", -1, UNSIGNED, PREDICT(LAST_MAIN_FRAME_TIME), ENCODING(UNSIGNED_VB), CONDITION(NOT_LOGGING_EVERY_FRAME)},
|
||||||
|
@ -291,13 +291,13 @@ typedef struct blackboxMainState_s {
|
||||||
uint16_t vbatLatest;
|
uint16_t vbatLatest;
|
||||||
uint16_t amperageLatest;
|
uint16_t amperageLatest;
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
int32_t BaroAlt;
|
int32_t BaroAlt;
|
||||||
#endif
|
#endif
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
int16_t magADC[XYZ_AXIS_COUNT];
|
int16_t magADC[XYZ_AXIS_COUNT];
|
||||||
#endif
|
#endif
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
int32_t sonarRaw;
|
int32_t sonarRaw;
|
||||||
#endif
|
#endif
|
||||||
uint16_t rssi;
|
uint16_t rssi;
|
||||||
|
@ -412,14 +412,14 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||||
return currentPidProfile->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].D != 0;
|
return currentPidProfile->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].D != 0;
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_MAG:
|
case FLIGHT_LOG_FIELD_CONDITION_MAG:
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
return sensors(SENSOR_MAG);
|
return sensors(SENSOR_MAG);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_BARO:
|
case FLIGHT_LOG_FIELD_CONDITION_BARO:
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
return sensors(SENSOR_BARO);
|
return sensors(SENSOR_BARO);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
|
@ -432,7 +432,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||||
return batteryConfig()->currentMeterSource == CURRENT_METER_ADC;
|
return batteryConfig()->currentMeterSource == CURRENT_METER_ADC;
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_SONAR:
|
case FLIGHT_LOG_FIELD_CONDITION_SONAR:
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
return feature(FEATURE_SONAR);
|
return feature(FEATURE_SONAR);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
|
@ -550,19 +550,19 @@ static void writeIntraframe(void)
|
||||||
blackboxWriteUnsignedVB(blackboxCurrent->amperageLatest);
|
blackboxWriteUnsignedVB(blackboxCurrent->amperageLatest);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
|
||||||
blackboxWriteSigned16VBArray(blackboxCurrent->magADC, XYZ_AXIS_COUNT);
|
blackboxWriteSigned16VBArray(blackboxCurrent->magADC, XYZ_AXIS_COUNT);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
|
||||||
blackboxWriteSignedVB(blackboxCurrent->BaroAlt);
|
blackboxWriteSignedVB(blackboxCurrent->BaroAlt);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) {
|
||||||
blackboxWriteSignedVB(blackboxCurrent->sonarRaw);
|
blackboxWriteSignedVB(blackboxCurrent->sonarRaw);
|
||||||
}
|
}
|
||||||
|
@ -678,7 +678,7 @@ static void writeInterframe(void)
|
||||||
deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperageLatest - blackboxLast->amperageLatest;
|
deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperageLatest - blackboxLast->amperageLatest;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
|
||||||
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
|
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
|
||||||
deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x];
|
deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x];
|
||||||
|
@ -686,13 +686,13 @@ static void writeInterframe(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
|
||||||
deltas[optionalFieldCount++] = blackboxCurrent->BaroAlt - blackboxLast->BaroAlt;
|
deltas[optionalFieldCount++] = blackboxCurrent->BaroAlt - blackboxLast->BaroAlt;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) {
|
||||||
deltas[optionalFieldCount++] = blackboxCurrent->sonarRaw - blackboxLast->sonarRaw;
|
deltas[optionalFieldCount++] = blackboxCurrent->sonarRaw - blackboxLast->sonarRaw;
|
||||||
}
|
}
|
||||||
|
@ -933,7 +933,7 @@ bool inMotorTestMode(void) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void writeGPSHomeFrame(void)
|
static void writeGPSHomeFrame(void)
|
||||||
{
|
{
|
||||||
blackboxWrite('H');
|
blackboxWrite('H');
|
||||||
|
@ -990,7 +990,7 @@ static void loadMainState(timeUs_t currentTimeUs)
|
||||||
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
|
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
|
||||||
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
|
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
|
||||||
blackboxCurrent->accSmooth[i] = acc.accSmooth[i];
|
blackboxCurrent->accSmooth[i] = acc.accSmooth[i];
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
blackboxCurrent->magADC[i] = mag.magADC[i];
|
blackboxCurrent->magADC[i] = mag.magADC[i];
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -1011,11 +1011,11 @@ static void loadMainState(timeUs_t currentTimeUs)
|
||||||
blackboxCurrent->vbatLatest = getBatteryVoltageLatest();
|
blackboxCurrent->vbatLatest = getBatteryVoltageLatest();
|
||||||
blackboxCurrent->amperageLatest = getAmperageLatest();
|
blackboxCurrent->amperageLatest = getAmperageLatest();
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
blackboxCurrent->BaroAlt = baro.BaroAlt;
|
blackboxCurrent->BaroAlt = baro.BaroAlt;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
// Store the raw sonar value without applying tilt correction
|
// Store the raw sonar value without applying tilt correction
|
||||||
blackboxCurrent->sonarRaw = sonarRead();
|
blackboxCurrent->sonarRaw = sonarRead();
|
||||||
#endif
|
#endif
|
||||||
|
@ -1387,7 +1387,7 @@ STATIC_UNIT_TESTED bool blackboxShouldLogIFrame(void)
|
||||||
* We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
|
* We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
|
||||||
* still be interpreted correctly.
|
* still be interpreted correctly.
|
||||||
*/
|
*/
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
STATIC_UNIT_TESTED bool blackboxShouldLogGpsHomeFrame(void)
|
STATIC_UNIT_TESTED bool blackboxShouldLogGpsHomeFrame(void)
|
||||||
{
|
{
|
||||||
if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
|
if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
|
||||||
|
@ -1442,7 +1442,7 @@ STATIC_UNIT_TESTED void blackboxLogIteration(timeUs_t currentTimeUs)
|
||||||
loadMainState(currentTimeUs);
|
loadMainState(currentTimeUs);
|
||||||
writeInterframe();
|
writeInterframe();
|
||||||
}
|
}
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
if (blackboxShouldLogGpsHomeFrame()) {
|
if (blackboxShouldLogGpsHomeFrame()) {
|
||||||
writeGPSHomeFrame();
|
writeGPSHomeFrame();
|
||||||
|
@ -1508,7 +1508,7 @@ void blackboxUpdate(timeUs_t currentTimeUs)
|
||||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||||
if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAYLEN(blackboxMainFields),
|
if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAYLEN(blackboxMainFields),
|
||||||
&blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
|
&blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER);
|
blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER);
|
||||||
} else
|
} else
|
||||||
|
@ -1516,7 +1516,7 @@ void blackboxUpdate(timeUs_t currentTimeUs)
|
||||||
blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER);
|
blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
case BLACKBOX_STATE_SEND_GPS_H_HEADER:
|
case BLACKBOX_STATE_SEND_GPS_H_HEADER:
|
||||||
blackboxReplenishHeaderBudget();
|
blackboxReplenishHeaderBudget();
|
||||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||||
|
|
|
@ -6,7 +6,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
|
|
||||||
#include "blackbox_encoding.h"
|
#include "blackbox_encoding.h"
|
||||||
#include "blackbox_io.h"
|
#include "blackbox_io.h"
|
||||||
|
|
|
@ -6,7 +6,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
|
|
||||||
#include "blackbox.h"
|
#include "blackbox.h"
|
||||||
#include "blackbox_io.h"
|
#include "blackbox_io.h"
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
@ -317,7 +317,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
case OME_VISIBLE:
|
case OME_VISIBLE:
|
||||||
if (IS_PRINTVALUE(p) && p->data) {
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
uint16_t *val = (uint16_t *)p->data;
|
uint16_t *val = (uint16_t *)p->data;
|
||||||
|
@ -756,7 +756,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
case OME_VISIBLE:
|
case OME_VISIBLE:
|
||||||
if (p->data) {
|
if (p->data) {
|
||||||
uint16_t *val = (uint16_t *)p->data;
|
uint16_t *val = (uint16_t *)p->data;
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(CMS) && defined(BLACKBOX)
|
#if defined(USE_CMS) && defined(USE_BLACKBOX)
|
||||||
|
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
|
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
@ -95,7 +95,7 @@ static OSD_Entry menuFeaturesEntries[] =
|
||||||
{
|
{
|
||||||
{"--- FEATURES ---", OME_Label, NULL, NULL, 0},
|
{"--- FEATURES ---", OME_Label, NULL, NULL, 0},
|
||||||
|
|
||||||
#if defined(BLACKBOX)
|
#if defined(USE_BLACKBOX)
|
||||||
{"BLACKBOX", OME_Submenu, cmsMenuChange, &cmsx_menuBlackbox, 0},
|
{"BLACKBOX", OME_Submenu, cmsMenuChange, &cmsx_menuBlackbox, 0},
|
||||||
#endif
|
#endif
|
||||||
#if defined(VTX_CONTROL)
|
#if defined(VTX_CONTROL)
|
||||||
|
@ -133,7 +133,7 @@ static OSD_Entry menuMainEntries[] =
|
||||||
|
|
||||||
{"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0},
|
{"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0},
|
||||||
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
|
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
{"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd, 0},
|
{"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd, 0},
|
||||||
#endif
|
#endif
|
||||||
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
|
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
|
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
|
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
|
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(OSD) && defined(CMS)
|
#if defined(USE_OSD) && defined(USE_CMS)
|
||||||
|
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
@ -76,7 +76,7 @@ OSD_Entry menuOsdActiveElemsEntries[] =
|
||||||
#endif // VTX
|
#endif // VTX
|
||||||
{"CURRENT (A)", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CURRENT_DRAW], 0},
|
{"CURRENT (A)", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CURRENT_DRAW], 0},
|
||||||
{"USED MAH", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAH_DRAWN], 0},
|
{"USED MAH", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAH_DRAWN], 0},
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
{"GPS SPEED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SPEED], 0},
|
{"GPS SPEED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SPEED], 0},
|
||||||
{"GPS SATS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SATS], 0},
|
{"GPS SATS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_SATS], 0},
|
||||||
{"GPS LAT", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_LAT], 0},
|
{"GPS LAT", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_GPS_LAT], 0},
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef CMS
|
#if defined(USE_CMS)
|
||||||
|
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
@ -33,6 +33,7 @@
|
||||||
#include "io/vtx_rtc6705.h"
|
#include "io/vtx_rtc6705.h"
|
||||||
#include "io/vtx_settings_config.h"
|
#include "io/vtx_settings_config.h"
|
||||||
|
|
||||||
|
#if defined(VTX_SETTINGS_CONFIG)
|
||||||
|
|
||||||
static uint8_t cmsx_vtxBand;
|
static uint8_t cmsx_vtxBand;
|
||||||
static uint8_t cmsx_vtxChannel;
|
static uint8_t cmsx_vtxChannel;
|
||||||
|
@ -98,4 +99,6 @@ CMS_Menu cmsx_menuVtxRTC6705 = {
|
||||||
.entries = cmsx_menuVtxEntries
|
.entries = cmsx_menuVtxEntries
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // VTX_SETTINGS_CONFIG
|
||||||
|
|
||||||
#endif // CMS
|
#endif // CMS
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(CMS) && defined(VTX_SMARTAUDIO)
|
#if defined(USE_CMS) && defined(VTX_SMARTAUDIO)
|
||||||
|
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(CMS) && defined(VTX_TRAMP)
|
#if defined(USE_CMS) && defined(VTX_TRAMP)
|
||||||
|
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
|
@ -39,7 +39,7 @@ typedef enum
|
||||||
OME_String,
|
OME_String,
|
||||||
OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's
|
OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's
|
||||||
//wlasciwosci elementow
|
//wlasciwosci elementow
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
OME_VISIBLE,
|
OME_VISIBLE,
|
||||||
#endif
|
#endif
|
||||||
OME_TAB,
|
OME_TAB,
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
|
|
||||||
|
|
||||||
#define DIGIT_TO_VAL(_x) (_x - '0')
|
#define DIGIT_TO_VAL(_x) (_x - '0')
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
|
|
||||||
#include "barometer_bmp085.h"
|
#include "barometer_bmp085.h"
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
|
|
||||||
#if defined(BARO_EOC_GPIO)
|
#if defined(BARO_EOC_GPIO)
|
||||||
|
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
|
|
||||||
#include "barometer_bmp280.h"
|
#include "barometer_bmp280.h"
|
||||||
|
|
||||||
#if defined(BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280))
|
#if defined(USE_BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280))
|
||||||
|
|
||||||
typedef struct bmp280_calib_param_s {
|
typedef struct bmp280_calib_param_s {
|
||||||
uint16_t dig_T1; /* calibration T1 data */
|
uint16_t dig_T1; /* calibration T1 data */
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#if defined(BARO) && (defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611))
|
#if defined(USE_BARO) && (defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611))
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
|
|
@ -56,7 +56,7 @@
|
||||||
#define CAMERA_CONTROL_PIN NONE
|
#define CAMERA_CONTROL_PIN NONE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -193,7 +193,7 @@ void cameraControlKeyPress(cameraControlKey_e key, uint32_t holdDurationMs)
|
||||||
(void) holdDurationMs;
|
(void) holdDurationMs;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
// Force OSD timeout so we are alone on the display.
|
// Force OSD timeout so we are alone on the display.
|
||||||
resumeRefreshAt = 0;
|
resumeRefreshAt = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#if defined(SONAR)
|
#if defined(USE_SONAR)
|
||||||
STATIC_UNIT_TESTED volatile int32_t measurement = -1;
|
STATIC_UNIT_TESTED volatile int32_t measurement = -1;
|
||||||
static uint32_t lastMeasurementAt;
|
static uint32_t lastMeasurementAt;
|
||||||
|
|
||||||
|
|
|
@ -2229,7 +2229,7 @@ static void cliExit(char *cmdline)
|
||||||
cliWriter = NULL;
|
cliWriter = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void cliGpsPassthrough(char *cmdline)
|
static void cliGpsPassthrough(char *cmdline)
|
||||||
{
|
{
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
|
@ -3007,7 +3007,7 @@ static void cliStatus(char *cmdline)
|
||||||
const int systemRate = getTaskDeltaTime(TASK_SYSTEM) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_SYSTEM)));
|
const int systemRate = getTaskDeltaTime(TASK_SYSTEM) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_SYSTEM)));
|
||||||
cliPrintLinef("CPU:%d%%, cycle time: %d, GYRO rate: %d, RX rate: %d, System rate: %d",
|
cliPrintLinef("CPU:%d%%, cycle time: %d, GYRO rate: %d, RX rate: %d, System rate: %d",
|
||||||
constrain(averageSystemLoadPercent, 0, 100), getTaskDeltaTime(TASK_GYROPID), gyroRate, rxRate, systemRate);
|
constrain(averageSystemLoadPercent, 0, 100), getTaskDeltaTime(TASK_GYROPID), gyroRate, rxRate, systemRate);
|
||||||
#if defined(OSD) || !defined(MINIMAL_CLI)
|
#if defined(USE_OSD) || !defined(MINIMAL_CLI)
|
||||||
/* Flag strings are present if OSD is compiled so may as well use them even with MINIMAL_CLI */
|
/* Flag strings are present if OSD is compiled so may as well use them even with MINIMAL_CLI */
|
||||||
cliPrint("Arming disable flags:");
|
cliPrint("Arming disable flags:");
|
||||||
armingDisableFlags_e flags = getArmingDisableFlags();
|
armingDisableFlags_e flags = getArmingDisableFlags();
|
||||||
|
@ -3121,7 +3121,7 @@ const cliResourceValue_t resourceTable[] = {
|
||||||
{ OWNER_PPMINPUT, PG_PPM_CONFIG, offsetof(ppmConfig_t, ioTag), 0 },
|
{ OWNER_PPMINPUT, PG_PPM_CONFIG, offsetof(ppmConfig_t, ioTag), 0 },
|
||||||
{ OWNER_PWMINPUT, PG_PWM_CONFIG, offsetof(pwmConfig_t, ioTags[0]), PWM_INPUT_PORT_COUNT },
|
{ OWNER_PWMINPUT, PG_PWM_CONFIG, offsetof(pwmConfig_t, ioTags[0]), PWM_INPUT_PORT_COUNT },
|
||||||
#endif
|
#endif
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
{ OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, offsetof(sonarConfig_t, triggerTag), 0 },
|
{ OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, offsetof(sonarConfig_t, triggerTag), 0 },
|
||||||
{ OWNER_SONAR_ECHO, PG_SONAR_CONFIG, offsetof(sonarConfig_t, echoTag), 0 },
|
{ OWNER_SONAR_ECHO, PG_SONAR_CONFIG, offsetof(sonarConfig_t, echoTag), 0 },
|
||||||
#endif
|
#endif
|
||||||
|
@ -3162,10 +3162,10 @@ const cliResourceValue_t resourceTable[] = {
|
||||||
{ OWNER_ADC_CURR, PG_ADC_CONFIG, offsetof(adcConfig_t, current.ioTag), 0 },
|
{ OWNER_ADC_CURR, PG_ADC_CONFIG, offsetof(adcConfig_t, current.ioTag), 0 },
|
||||||
{ OWNER_ADC_EXT, PG_ADC_CONFIG, offsetof(adcConfig_t, external1.ioTag), 0 },
|
{ OWNER_ADC_EXT, PG_ADC_CONFIG, offsetof(adcConfig_t, external1.ioTag), 0 },
|
||||||
#endif
|
#endif
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
{ OWNER_BARO_CS, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_csn), 0 },
|
{ OWNER_BARO_CS, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_csn), 0 },
|
||||||
#endif
|
#endif
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
{ OWNER_COMPASS_CS, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_spi_csn), 0 },
|
{ OWNER_COMPASS_CS, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_spi_csn), 0 },
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
@ -3635,7 +3635,7 @@ const clicmd_t cmdTable[] = {
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet),
|
CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet),
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
|
CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
|
||||||
#endif
|
#endif
|
||||||
CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
|
CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
|
||||||
|
|
|
@ -310,7 +310,7 @@ void activateConfig(void)
|
||||||
useRcControlsConfig(currentPidProfile);
|
useRcControlsConfig(currentPidProfile);
|
||||||
useAdjustmentConfig(currentPidProfile);
|
useAdjustmentConfig(currentPidProfile);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
gpsUsePIDs(currentPidProfile);
|
gpsUsePIDs(currentPidProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -102,7 +102,7 @@ enum {
|
||||||
|
|
||||||
#define AIRMODE_THOTTLE_THRESHOLD 1350 // Make configurable in the future. ~35% throttle should be fine
|
#define AIRMODE_THOTTLE_THRESHOLD 1350 // Make configurable in the future. ~35% throttle should be fine
|
||||||
|
|
||||||
#if defined(GPS) || defined(MAG)
|
#if defined(USE_GPS) || defined(USE_MAG)
|
||||||
int16_t magHold;
|
int16_t magHold;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -130,7 +130,7 @@ void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsD
|
||||||
|
|
||||||
static bool isCalibrating(void)
|
static bool isCalibrating(void)
|
||||||
{
|
{
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (sensors(SENSOR_BARO) && !isBaroCalibrationComplete()) {
|
if (sensors(SENSOR_BARO) && !isBaroCalibrationComplete()) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -237,7 +237,7 @@ void disarm(void)
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
DISABLE_ARMING_FLAG(ARMED);
|
DISABLE_ARMING_FLAG(ARMED);
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
if (blackboxConfig()->device) {
|
if (blackboxConfig()->device) {
|
||||||
blackboxFinish();
|
blackboxFinish();
|
||||||
}
|
}
|
||||||
|
@ -289,7 +289,7 @@ void tryArm(void)
|
||||||
lastArmingDisabledReason = 0;
|
lastArmingDisabledReason = 0;
|
||||||
|
|
||||||
//beep to indicate arming
|
//beep to indicate arming
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) {
|
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) {
|
||||||
beeper(BEEPER_ARMING_GPS_FIX);
|
beeper(BEEPER_ARMING_GPS_FIX);
|
||||||
} else {
|
} else {
|
||||||
|
@ -349,7 +349,7 @@ static void updateInflightCalibrationState(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(GPS) || defined(MAG)
|
#if defined(USE_GPS) || defined(USE_MAG)
|
||||||
void updateMagHold(void)
|
void updateMagHold(void)
|
||||||
{
|
{
|
||||||
if (ABS(rcCommand[YAW]) < 15 && FLIGHT_MODE(MAG_MODE)) {
|
if (ABS(rcCommand[YAW]) < 15 && FLIGHT_MODE(MAG_MODE)) {
|
||||||
|
@ -509,9 +509,9 @@ void processRx(timeUs_t currentTimeUs)
|
||||||
DISABLE_ARMING_FLAG(WAS_ARMED_WITH_PREARM);
|
DISABLE_ARMING_FLAG(WAS_ARMED_WITH_PREARM);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(ACC) || defined(MAG)
|
#if defined(USE_ACC) || defined(USE_MAG)
|
||||||
if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
|
||||||
#if defined(GPS) || defined(MAG)
|
#if defined(USE_GPS) || defined(USE_MAG)
|
||||||
if (IS_RC_MODE_ACTIVE(BOXMAG)) {
|
if (IS_RC_MODE_ACTIVE(BOXMAG)) {
|
||||||
if (!FLIGHT_MODE(MAG_MODE)) {
|
if (!FLIGHT_MODE(MAG_MODE)) {
|
||||||
ENABLE_FLIGHT_MODE(MAG_MODE);
|
ENABLE_FLIGHT_MODE(MAG_MODE);
|
||||||
|
@ -536,7 +536,7 @@ void processRx(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (sensors(SENSOR_GPS)) {
|
if (sensors(SENSOR_GPS)) {
|
||||||
updateGpsWaypointsAndMode();
|
updateGpsWaypointsAndMode();
|
||||||
}
|
}
|
||||||
|
@ -594,13 +594,13 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
|
||||||
gyroReadTemperature();
|
gyroReadTemperature();
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
updateMagHold();
|
updateMagHold();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
||||||
updateRcCommands();
|
updateRcCommands();
|
||||||
if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) {
|
if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) {
|
||||||
|
@ -632,7 +632,7 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
|
||||||
|
|
||||||
processRcCommand();
|
processRcCommand();
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (sensors(SENSOR_GPS)) {
|
if (sensors(SENSOR_GPS)) {
|
||||||
if ((FLIGHT_MODE(GPS_HOME_MODE) || FLIGHT_MODE(GPS_HOLD_MODE)) && STATE(GPS_FIX_HOME)) {
|
if ((FLIGHT_MODE(GPS_HOME_MODE) || FLIGHT_MODE(GPS_HOLD_MODE)) && STATE(GPS_FIX_HOME)) {
|
||||||
updateGpsStateForHomeAndHoldMode();
|
updateGpsStateForHomeAndHoldMode();
|
||||||
|
@ -644,7 +644,7 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
|
||||||
afatfs_poll();
|
afatfs_poll();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
if (!cliMode && blackboxConfig()->device) {
|
if (!cliMode && blackboxConfig()->device) {
|
||||||
blackboxUpdate(currentTimeUs);
|
blackboxUpdate(currentTimeUs);
|
||||||
}
|
}
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
|
|
||||||
#if defined(GPS) || defined(MAG)
|
#if defined(USE_GPS) || defined(USE_MAG)
|
||||||
extern int16_t magHold;
|
extern int16_t magHold;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -472,13 +472,13 @@ void init(void)
|
||||||
cameraControlInit();
|
cameraControlInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SONAR_SOFTSERIAL2_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL2)
|
#if defined(SONAR_SOFTSERIAL2_EXCLUSIVE) && defined(USE_SONAR) && defined(USE_SOFTSERIAL2)
|
||||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SONAR_SOFTSERIAL1_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL1)
|
#if defined(SONAR_SOFTSERIAL1_EXCLUSIVE) && defined(USE_SONAR) && defined(USE_SOFTSERIAL1)
|
||||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
||||||
}
|
}
|
||||||
|
@ -550,15 +550,15 @@ void init(void)
|
||||||
/*
|
/*
|
||||||
* CMS, display devices and OSD
|
* CMS, display devices and OSD
|
||||||
*/
|
*/
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
cmsInit();
|
cmsInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if (defined(OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(CMS)) || defined(USE_OSD_SLAVE))
|
#if (defined(USE_OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS)) || defined(USE_OSD_SLAVE))
|
||||||
displayPort_t *osdDisplayPort = NULL;
|
displayPort_t *osdDisplayPort = NULL;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(OSD) && !defined(USE_OSD_SLAVE)
|
#if defined(USE_OSD) && !defined(USE_OSD_SLAVE)
|
||||||
//The OSD need to be initialised after GYRO to avoid GYRO initialisation failure on some targets
|
//The OSD need to be initialised after GYRO to avoid GYRO initialisation failure on some targets
|
||||||
|
|
||||||
if (feature(FEATURE_OSD)) {
|
if (feature(FEATURE_OSD)) {
|
||||||
|
@ -573,7 +573,7 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_OSD_SLAVE) && !defined(OSD)
|
#if defined(USE_OSD_SLAVE) && !defined(USE_OSD)
|
||||||
#if defined(USE_MAX7456)
|
#if defined(USE_MAX7456)
|
||||||
// If there is a max7456 chip for the OSD then use it
|
// If there is a max7456 chip for the OSD then use it
|
||||||
osdDisplayPort = max7456DisplayPortInit(vcdProfile());
|
osdDisplayPort = max7456DisplayPortInit(vcdProfile());
|
||||||
|
@ -582,7 +582,7 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(CMS) && defined(USE_MSP_DISPLAYPORT)
|
#if defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT)
|
||||||
// If BFOSD is not active, then register MSP_DISPLAYPORT as a CMS device.
|
// If BFOSD is not active, then register MSP_DISPLAYPORT as a CMS device.
|
||||||
if (!osdDisplayPort)
|
if (!osdDisplayPort)
|
||||||
cmsDisplayPortRegister(displayPortMspInit());
|
cmsDisplayPortRegister(displayPortMspInit());
|
||||||
|
@ -596,7 +596,7 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
gpsInit();
|
gpsInit();
|
||||||
navigationInit();
|
navigationInit();
|
||||||
|
@ -650,7 +650,7 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
blackboxInit();
|
blackboxInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -658,7 +658,7 @@ void init(void)
|
||||||
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
||||||
}
|
}
|
||||||
gyroStartCalibration(false);
|
gyroStartCalibration(false);
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
|
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -413,7 +413,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
#ifdef USE_OSD_SLAVE
|
#ifdef USE_OSD_SLAVE
|
||||||
sbufWriteU8(dst, 1); // 1 == OSD
|
sbufWriteU8(dst, 1); // 1 == OSD
|
||||||
#else
|
#else
|
||||||
#if defined(OSD) && defined(USE_MAX7456)
|
#if defined(USE_OSD) && defined(USE_MAX7456)
|
||||||
sbufWriteU8(dst, 2); // 2 == FC with OSD
|
sbufWriteU8(dst, 2); // 2 == FC with OSD
|
||||||
#else
|
#else
|
||||||
sbufWriteU8(dst, 0); // 0 == FC
|
sbufWriteU8(dst, 0); // 0 == FC
|
||||||
|
@ -617,7 +617,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
#define OSD_FLAGS_OSD_HARDWARE_MAX_7456 (1 << 4)
|
#define OSD_FLAGS_OSD_HARDWARE_MAX_7456 (1 << 4)
|
||||||
|
|
||||||
uint8_t osdFlags = 0;
|
uint8_t osdFlags = 0;
|
||||||
#if defined(OSD)
|
#if defined(USE_OSD)
|
||||||
osdFlags |= OSD_FLAGS_OSD_FEATURE;
|
osdFlags |= OSD_FLAGS_OSD_FEATURE;
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_OSD_SLAVE)
|
#if defined(USE_OSD_SLAVE)
|
||||||
|
@ -636,7 +636,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
sbufWriteU8(dst, 0);
|
sbufWriteU8(dst, 0);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
// OSD specific, not applicable to OSD slaves.
|
// OSD specific, not applicable to OSD slaves.
|
||||||
|
|
||||||
// Configuration
|
// Configuration
|
||||||
|
@ -840,7 +840,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_ALTITUDE:
|
case MSP_ALTITUDE:
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
sbufWriteU32(dst, getEstimatedAltitude());
|
sbufWriteU32(dst, getEstimatedAltitude());
|
||||||
#else
|
#else
|
||||||
sbufWriteU32(dst, 0);
|
sbufWriteU32(dst, 0);
|
||||||
|
@ -849,7 +849,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SONAR_ALTITUDE:
|
case MSP_SONAR_ALTITUDE:
|
||||||
#if defined(SONAR)
|
#if defined(USE_SONAR)
|
||||||
sbufWriteU32(dst, sonarGetLatestAltitude());
|
sbufWriteU32(dst, sonarGetLatestAltitude());
|
||||||
#else
|
#else
|
||||||
sbufWriteU32(dst, 0);
|
sbufWriteU32(dst, 0);
|
||||||
|
@ -929,7 +929,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
sbufWriteU16(dst, motorConfig()->mincommand);
|
sbufWriteU16(dst, motorConfig()->mincommand);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
case MSP_COMPASS_CONFIG:
|
case MSP_COMPASS_CONFIG:
|
||||||
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
||||||
break;
|
break;
|
||||||
|
@ -945,7 +945,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
case MSP_GPS_CONFIG:
|
case MSP_GPS_CONFIG:
|
||||||
sbufWriteU8(dst, gpsConfig()->provider);
|
sbufWriteU8(dst, gpsConfig()->provider);
|
||||||
sbufWriteU8(dst, gpsConfig()->sbasMode);
|
sbufWriteU8(dst, gpsConfig()->sbasMode);
|
||||||
|
@ -1103,7 +1103,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_BLACKBOX_CONFIG:
|
case MSP_BLACKBOX_CONFIG:
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
sbufWriteU8(dst, 1); //Blackbox supported
|
sbufWriteU8(dst, 1); //Blackbox supported
|
||||||
sbufWriteU8(dst, blackboxConfig()->device);
|
sbufWriteU8(dst, blackboxConfig()->device);
|
||||||
sbufWriteU8(dst, blackboxGetRateNum());
|
sbufWriteU8(dst, blackboxGetRateNum());
|
||||||
|
@ -1255,7 +1255,7 @@ static mspResult_e mspFcProcessOutCommandWithArg(uint8_t cmdMSP, sbuf_t *arg, sb
|
||||||
}
|
}
|
||||||
#endif // USE_OSD_SLAVE
|
#endif // USE_OSD_SLAVE
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void mspFcWpCommand(sbuf_t *dst, sbuf_t *src)
|
static void mspFcWpCommand(sbuf_t *dst, sbuf_t *src)
|
||||||
{
|
{
|
||||||
uint8_t wp_no;
|
uint8_t wp_no;
|
||||||
|
@ -1316,7 +1316,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
uint8_t value;
|
uint8_t value;
|
||||||
const unsigned int dataSize = sbufBytesRemaining(src);
|
const unsigned int dataSize = sbufBytesRemaining(src);
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
uint8_t wp_no;
|
uint8_t wp_no;
|
||||||
int32_t lat = 0, lon = 0, alt = 0;
|
int32_t lat = 0, lon = 0, alt = 0;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1352,7 +1352,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if defined(GPS) || defined(MAG)
|
#if defined(USE_GPS) || defined(USE_MAG)
|
||||||
case MSP_SET_HEADING:
|
case MSP_SET_HEADING:
|
||||||
magHold = sbufReadU16(src);
|
magHold = sbufReadU16(src);
|
||||||
break;
|
break;
|
||||||
|
@ -1470,7 +1470,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
motorConfigMutable()->mincommand = sbufReadU16(src);
|
motorConfigMutable()->mincommand = sbufReadU16(src);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
case MSP_SET_GPS_CONFIG:
|
case MSP_SET_GPS_CONFIG:
|
||||||
gpsConfigMutable()->provider = sbufReadU8(src);
|
gpsConfigMutable()->provider = sbufReadU8(src);
|
||||||
gpsConfigMutable()->sbasMode = sbufReadU8(src);
|
gpsConfigMutable()->sbasMode = sbufReadU8(src);
|
||||||
|
@ -1479,7 +1479,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
case MSP_SET_COMPASS_CONFIG:
|
case MSP_SET_COMPASS_CONFIG:
|
||||||
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
|
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
|
||||||
break;
|
break;
|
||||||
|
@ -1652,7 +1652,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
readEEPROM();
|
readEEPROM();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
case MSP_SET_BLACKBOX_CONFIG:
|
case MSP_SET_BLACKBOX_CONFIG:
|
||||||
// Don't allow config to be updated while Blackbox is logging
|
// Don't allow config to be updated while Blackbox is logging
|
||||||
if (blackboxMayEditConfig()) {
|
if (blackboxMayEditConfig()) {
|
||||||
|
@ -1745,7 +1745,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
case MSP_SET_RAW_GPS:
|
case MSP_SET_RAW_GPS:
|
||||||
if (sbufReadU8(src)) {
|
if (sbufReadU8(src)) {
|
||||||
ENABLE_STATE(GPS_FIX);
|
ENABLE_STATE(GPS_FIX);
|
||||||
|
@ -2066,7 +2066,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
|
batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if defined(OSD) || defined (USE_OSD_SLAVE)
|
#if defined(USE_OSD) || defined (USE_OSD_SLAVE)
|
||||||
case MSP_SET_OSD_CONFIG:
|
case MSP_SET_OSD_CONFIG:
|
||||||
{
|
{
|
||||||
const uint8_t addr = sbufReadU8(src);
|
const uint8_t addr = sbufReadU8(src);
|
||||||
|
@ -2078,7 +2078,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
#else
|
#else
|
||||||
sbufReadU8(src); // Skip video system
|
sbufReadU8(src); // Skip video system
|
||||||
#endif
|
#endif
|
||||||
#if defined(OSD)
|
#if defined(USE_OSD)
|
||||||
osdConfigMutable()->units = sbufReadU8(src);
|
osdConfigMutable()->units = sbufReadU8(src);
|
||||||
|
|
||||||
// Alarms
|
// Alarms
|
||||||
|
@ -2093,7 +2093,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
} else if ((int8_t)addr == -2) {
|
} else if ((int8_t)addr == -2) {
|
||||||
#if defined(OSD)
|
#if defined(USE_OSD)
|
||||||
// Timers
|
// Timers
|
||||||
uint8_t index = sbufReadU8(src);
|
uint8_t index = sbufReadU8(src);
|
||||||
if (index > OSD_TIMER_COUNT) {
|
if (index > OSD_TIMER_COUNT) {
|
||||||
|
@ -2103,7 +2103,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
#endif
|
#endif
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
} else {
|
} else {
|
||||||
#if defined(OSD)
|
#if defined(USE_OSD)
|
||||||
const uint16_t value = sbufReadU16(src);
|
const uint16_t value = sbufReadU16(src);
|
||||||
|
|
||||||
/* Get screen index, 0 is post flight statistics, 1 and above are in flight OSD screens */
|
/* Get screen index, 0 is post flight statistics, 1 and above are in flight OSD screens */
|
||||||
|
@ -2173,7 +2173,7 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro
|
||||||
mspFc4waySerialCommand(dst, src, mspPostProcessFn);
|
mspFc4waySerialCommand(dst, src, mspPostProcessFn);
|
||||||
ret = MSP_RESULT_ACK;
|
ret = MSP_RESULT_ACK;
|
||||||
#endif
|
#endif
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
} else if (cmdMSP == MSP_WP) {
|
} else if (cmdMSP == MSP_WP) {
|
||||||
mspFcWpCommand(dst, src);
|
mspFcWpCommand(dst, src);
|
||||||
ret = MSP_RESULT_ACK;
|
ret = MSP_RESULT_ACK;
|
||||||
|
|
|
@ -167,19 +167,19 @@ void initActiveBoxIds(void)
|
||||||
BME(BOXHEADADJ);
|
BME(BOXHEADADJ);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
BME(BOXBARO);
|
BME(BOXBARO);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
BME(BOXMAG);
|
BME(BOXMAG);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
BME(BOXGPSHOME);
|
BME(BOXGPSHOME);
|
||||||
BME(BOXGPSHOLD);
|
BME(BOXGPSHOLD);
|
||||||
|
@ -187,7 +187,7 @@ void initActiveBoxIds(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
if (feature(FEATURE_SONAR)) {
|
if (feature(FEATURE_SONAR)) {
|
||||||
BME(BOXSONAR);
|
BME(BOXSONAR);
|
||||||
}
|
}
|
||||||
|
@ -207,7 +207,7 @@ void initActiveBoxIds(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
BME(BOXBLACKBOX);
|
BME(BOXBLACKBOX);
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
BME(BOXBLACKBOXERASE);
|
BME(BOXBLACKBOXERASE);
|
||||||
|
|
|
@ -138,19 +138,19 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs)
|
||||||
processRx(currentTimeUs);
|
processRx(currentTimeUs);
|
||||||
isRXDataNew = true;
|
isRXDataNew = true;
|
||||||
|
|
||||||
#if !defined(BARO) && !defined(SONAR)
|
#if !defined(USE_BARO) && !defined(USE_SONAR)
|
||||||
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
||||||
updateRcCommands();
|
updateRcCommands();
|
||||||
#endif
|
#endif
|
||||||
updateArmingStatus();
|
updateArmingStatus();
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
updateAltHoldState();
|
updateAltHoldState();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
if (sensors(SENSOR_SONAR)) {
|
if (sensors(SENSOR_SONAR)) {
|
||||||
updateSonarAltHoldState();
|
updateSonarAltHoldState();
|
||||||
}
|
}
|
||||||
|
@ -158,7 +158,7 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
static void taskUpdateCompass(timeUs_t currentTimeUs)
|
static void taskUpdateCompass(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
|
@ -167,7 +167,7 @@ static void taskUpdateCompass(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
static void taskUpdateBaro(timeUs_t currentTimeUs)
|
static void taskUpdateBaro(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
UNUSED(currentTimeUs);
|
UNUSED(currentTimeUs);
|
||||||
|
@ -181,14 +181,14 @@ static void taskUpdateBaro(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
static void taskCalculateAltitude(timeUs_t currentTimeUs)
|
static void taskCalculateAltitude(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
if (false
|
if (false
|
||||||
#if defined(BARO)
|
#if defined(USE_BARO)
|
||||||
|| (sensors(SENSOR_BARO) && isBaroReady())
|
|| (sensors(SENSOR_BARO) && isBaroReady())
|
||||||
#endif
|
#endif
|
||||||
#if defined(SONAR)
|
#if defined(USE_SONAR)
|
||||||
|| sensors(SENSOR_SONAR)
|
|| sensors(SENSOR_SONAR)
|
||||||
#endif
|
#endif
|
||||||
) {
|
) {
|
||||||
|
@ -281,19 +281,19 @@ void fcTasksInit(void)
|
||||||
#ifdef BEEPER
|
#ifdef BEEPER
|
||||||
setTaskEnabled(TASK_BEEPER, true);
|
setTaskEnabled(TASK_BEEPER, true);
|
||||||
#endif
|
#endif
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
setTaskEnabled(TASK_GPS, feature(FEATURE_GPS));
|
setTaskEnabled(TASK_GPS, feature(FEATURE_GPS));
|
||||||
#endif
|
#endif
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
|
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
|
||||||
#endif
|
#endif
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
|
setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
|
||||||
#endif
|
#endif
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
setTaskEnabled(TASK_SONAR, sensors(SENSOR_SONAR));
|
setTaskEnabled(TASK_SONAR, sensors(SENSOR_SONAR));
|
||||||
#endif
|
#endif
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || sensors(SENSOR_SONAR));
|
setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || sensors(SENSOR_SONAR));
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_DASHBOARD
|
#ifdef USE_DASHBOARD
|
||||||
|
@ -317,7 +317,7 @@ void fcTasksInit(void)
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
|
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
|
||||||
#endif
|
#endif
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
|
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
|
@ -326,7 +326,7 @@ void fcTasksInit(void)
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
setTaskEnabled(TASK_ESC_SENSOR, feature(FEATURE_ESC_SENSOR));
|
setTaskEnabled(TASK_ESC_SENSOR, feature(FEATURE_ESC_SENSOR));
|
||||||
#endif
|
#endif
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
#ifdef USE_MSP_DISPLAYPORT
|
#ifdef USE_MSP_DISPLAYPORT
|
||||||
setTaskEnabled(TASK_CMS, true);
|
setTaskEnabled(TASK_CMS, true);
|
||||||
#else
|
#else
|
||||||
|
@ -463,7 +463,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
[TASK_GPS] = {
|
[TASK_GPS] = {
|
||||||
.taskName = "GPS",
|
.taskName = "GPS",
|
||||||
.taskFunc = gpsUpdate,
|
.taskFunc = gpsUpdate,
|
||||||
|
@ -472,7 +472,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
[TASK_COMPASS] = {
|
[TASK_COMPASS] = {
|
||||||
.taskName = "COMPASS",
|
.taskName = "COMPASS",
|
||||||
.taskFunc = taskUpdateCompass,
|
.taskFunc = taskUpdateCompass,
|
||||||
|
@ -481,7 +481,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
[TASK_BARO] = {
|
[TASK_BARO] = {
|
||||||
.taskName = "BARO",
|
.taskName = "BARO",
|
||||||
.taskFunc = taskUpdateBaro,
|
.taskFunc = taskUpdateBaro,
|
||||||
|
@ -490,7 +490,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
[TASK_SONAR] = {
|
[TASK_SONAR] = {
|
||||||
.taskName = "SONAR",
|
.taskName = "SONAR",
|
||||||
.taskFunc = sonarUpdate,
|
.taskFunc = sonarUpdate,
|
||||||
|
@ -499,7 +499,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
[TASK_ALTITUDE] = {
|
[TASK_ALTITUDE] = {
|
||||||
.taskName = "ALTITUDE",
|
.taskName = "ALTITUDE",
|
||||||
.taskFunc = taskCalculateAltitude,
|
.taskFunc = taskCalculateAltitude,
|
||||||
|
@ -517,7 +517,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
[TASK_OSD] = {
|
[TASK_OSD] = {
|
||||||
.taskName = "OSD",
|
.taskName = "OSD",
|
||||||
.taskFunc = osdUpdate,
|
.taskFunc = osdUpdate,
|
||||||
|
@ -562,7 +562,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
[TASK_CMS] = {
|
[TASK_CMS] = {
|
||||||
.taskName = "CMS",
|
.taskName = "CMS",
|
||||||
.taskFunc = cmsHandler,
|
.taskFunc = cmsHandler,
|
||||||
|
|
|
@ -141,7 +141,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
static uint8_t rcDisarmTicks;
|
static uint8_t rcDisarmTicks;
|
||||||
static bool doNotRepeat;
|
static bool doNotRepeat;
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
if (cmsInMenu) {
|
if (cmsInMenu) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -224,13 +224,13 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
// GYRO calibration
|
// GYRO calibration
|
||||||
gyroStartCalibration(false);
|
gyroStartCalibration(false);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
GPS_reset_home_position();
|
GPS_reset_home_position();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (sensors(SENSOR_BARO))
|
if (sensors(SENSOR_BARO))
|
||||||
baroSetCalibrationCycles(10); // calibrate baro to new ground level (10 * 25 ms = ~250 ms non blocking)
|
baroSetCalibrationCycles(10); // calibrate baro to new ground level (10 * 25 ms = ~250 ms non blocking)
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -29,7 +29,7 @@ uint16_t flightModeFlags = 0;
|
||||||
|
|
||||||
static uint32_t enabledSensors = 0;
|
static uint32_t enabledSensors = 0;
|
||||||
|
|
||||||
#if defined(OSD) || !defined(MINIMAL_CLI)
|
#if defined(USE_OSD) || !defined(MINIMAL_CLI)
|
||||||
const char *armingDisableFlagNames[]= {
|
const char *armingDisableFlagNames[]= {
|
||||||
"NOGYRO", "FAILSAFE", "RXLOSS", "BADRX", "BOXFAILSAFE",
|
"NOGYRO", "FAILSAFE", "RXLOSS", "BADRX", "BOXFAILSAFE",
|
||||||
"THROTTLE", "ANGLE", "BOOTGRACE", "NOPREARM", "LOAD",
|
"THROTTLE", "ANGLE", "BOOTGRACE", "NOPREARM", "LOAD",
|
||||||
|
|
|
@ -56,7 +56,7 @@ typedef enum {
|
||||||
|
|
||||||
#define NUM_ARMING_DISABLE_FLAGS 17
|
#define NUM_ARMING_DISABLE_FLAGS 17
|
||||||
|
|
||||||
#if defined(OSD) || !defined(MINIMAL_CLI)
|
#if defined(USE_OSD) || !defined(MINIMAL_CLI)
|
||||||
extern const char *armingDisableFlagNames[NUM_ARMING_DISABLE_FLAGS];
|
extern const char *armingDisableFlagNames[NUM_ARMING_DISABLE_FLAGS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -97,13 +97,13 @@ const char * const lookupTableGyroHardware[] = {
|
||||||
"BMI160", "FAKE"
|
"BMI160", "FAKE"
|
||||||
};
|
};
|
||||||
|
|
||||||
#if defined(USE_SENSOR_NAMES) || defined(BARO)
|
#if defined(USE_SENSOR_NAMES) || defined(USE_BARO)
|
||||||
// sync with baroSensor_e
|
// sync with baroSensor_e
|
||||||
const char * const lookupTableBaroHardware[] = {
|
const char * const lookupTableBaroHardware[] = {
|
||||||
"AUTO", "NONE", "BMP085", "MS5611", "BMP280"
|
"AUTO", "NONE", "BMP085", "MS5611", "BMP280"
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_SENSOR_NAMES) || defined(MAG)
|
#if defined(USE_SENSOR_NAMES) || defined(USE_MAG)
|
||||||
// sync with magSensor_e
|
// sync with magSensor_e
|
||||||
const char * const lookupTableMagHardware[] = {
|
const char * const lookupTableMagHardware[] = {
|
||||||
"AUTO", "NONE", "HMC5883", "AK8975", "AK8963"
|
"AUTO", "NONE", "HMC5883", "AK8975", "AK8963"
|
||||||
|
@ -134,7 +134,7 @@ static const char * const lookupTableAlignment[] = {
|
||||||
"CW270FLIP"
|
"CW270FLIP"
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static const char * const lookupTableGPSProvider[] = {
|
static const char * const lookupTableGPSProvider[] = {
|
||||||
"NMEA", "UBLOX"
|
"NMEA", "UBLOX"
|
||||||
};
|
};
|
||||||
|
@ -158,7 +158,7 @@ static const char * const lookupTableGimbalMode[] = {
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
static const char * const lookupTableBlackboxDevice[] = {
|
static const char * const lookupTableBlackboxDevice[] = {
|
||||||
"NONE", "SPIFLASH", "SDCARD", "SERIAL"
|
"NONE", "SPIFLASH", "SDCARD", "SERIAL"
|
||||||
};
|
};
|
||||||
|
@ -208,7 +208,7 @@ static const char * const lookupTableGyroLpf[] = {
|
||||||
"EXPERIMENTAL"
|
"EXPERIMENTAL"
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
static const char * const lookupTableOsdType[] = {
|
static const char * const lookupTableOsdType[] = {
|
||||||
"AUTO",
|
"AUTO",
|
||||||
"PAL",
|
"PAL",
|
||||||
|
@ -265,11 +265,11 @@ const lookupTableEntry_t lookupTables[] = {
|
||||||
{ lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
|
{ lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
|
||||||
{ lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
|
{ lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
|
||||||
{ lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
|
{ lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
{ lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
|
{ lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
|
||||||
{ lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
|
{ lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
|
||||||
#endif
|
#endif
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
{ lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
|
{ lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
|
||||||
#endif
|
#endif
|
||||||
{ lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
|
{ lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
|
||||||
|
@ -286,10 +286,10 @@ const lookupTableEntry_t lookupTables[] = {
|
||||||
{ lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
|
{ lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
|
||||||
{ lookupTableGyroHardware, sizeof(lookupTableGyroHardware) / sizeof(char *) },
|
{ lookupTableGyroHardware, sizeof(lookupTableGyroHardware) / sizeof(char *) },
|
||||||
{ lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
|
{ lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
{ lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
|
{ lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
|
||||||
#endif
|
#endif
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
{ lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
|
{ lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
|
||||||
#endif
|
#endif
|
||||||
{ debugModeNames, sizeof(debugModeNames) / sizeof(char *) },
|
{ debugModeNames, sizeof(debugModeNames) / sizeof(char *) },
|
||||||
|
@ -300,7 +300,7 @@ const lookupTableEntry_t lookupTables[] = {
|
||||||
{ lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
|
{ lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
|
||||||
{ lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) },
|
{ lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) },
|
||||||
{ lookupTableCrashRecovery, sizeof(lookupTableCrashRecovery) / sizeof(char *) },
|
{ lookupTableCrashRecovery, sizeof(lookupTableCrashRecovery) / sizeof(char *) },
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
|
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_CAMERA_CONTROL
|
#ifdef USE_CAMERA_CONTROL
|
||||||
|
@ -347,7 +347,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "acc_trim_roll", VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, accelerometerTrims.values.roll) },
|
{ "acc_trim_roll", VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, accelerometerTrims.values.roll) },
|
||||||
|
|
||||||
// PG_COMPASS_CONFIG
|
// PG_COMPASS_CONFIG
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
{ "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_align) },
|
{ "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_align) },
|
||||||
{ "mag_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_bustype) },
|
{ "mag_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_bustype) },
|
||||||
{ "mag_i2c_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2CDEV_COUNT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_i2c_device) },
|
{ "mag_i2c_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2CDEV_COUNT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_i2c_device) },
|
||||||
|
@ -361,7 +361,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_BAROMETER_CONFIG
|
// PG_BAROMETER_CONFIG
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
{ "baro_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_bustype) },
|
{ "baro_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_bustype) },
|
||||||
{ "baro_spi_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_device) },
|
{ "baro_spi_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_device) },
|
||||||
{ "baro_i2c_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_i2c_device) },
|
{ "baro_i2c_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_i2c_device) },
|
||||||
|
@ -407,7 +407,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_BLACKBOX_CONFIG
|
// PG_BLACKBOX_CONFIG
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
{ "blackbox_p_ratio", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, p_denom) },
|
{ "blackbox_p_ratio", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, p_denom) },
|
||||||
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
|
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
|
||||||
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, on_motor_test) },
|
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, on_motor_test) },
|
||||||
|
@ -537,7 +537,7 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
|
|
||||||
// PG_GPS_CONFIG
|
// PG_GPS_CONFIG
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
{ "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, PG_GPS_CONFIG, offsetof(gpsConfig_t, provider) },
|
{ "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, PG_GPS_CONFIG, offsetof(gpsConfig_t, provider) },
|
||||||
{ "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbasMode) },
|
{ "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbasMode) },
|
||||||
{ "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoConfig) },
|
{ "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoConfig) },
|
||||||
|
@ -545,7 +545,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_NAVIGATION_CONFIG
|
// PG_NAVIGATION_CONFIG
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
{ "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, gps_wp_radius) },
|
{ "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, gps_wp_radius) },
|
||||||
{ "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_controls_heading) },
|
{ "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_controls_heading) },
|
||||||
{ "nav_speed_min", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 10, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_speed_min) },
|
{ "nav_speed_min", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 10, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_speed_min) },
|
||||||
|
@ -554,7 +554,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_AIRPLANE_CONFIG
|
// PG_AIRPLANE_CONFIG
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
{ "fixedwing_althold_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_AIRPLANE_CONFIG, offsetof(airplaneConfig_t, fixedwing_althold_reversed) },
|
{ "fixedwing_althold_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_AIRPLANE_CONFIG, offsetof(airplaneConfig_t, fixedwing_althold_reversed) },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -623,7 +623,7 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
{ "horizon_tilt_effect", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 250 }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_effect) },
|
{ "horizon_tilt_effect", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 250 }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_effect) },
|
||||||
{ "horizon_tilt_expert_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_expert_mode) },
|
{ "horizon_tilt_expert_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_expert_mode) },
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].P) },
|
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].P) },
|
||||||
{ "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].I) },
|
{ "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].I) },
|
||||||
{ "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].D) },
|
{ "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].D) },
|
||||||
|
@ -641,7 +641,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "tlm_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_inverted) },
|
{ "tlm_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_inverted) },
|
||||||
{ "tlm_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, halfDuplex) },
|
{ "tlm_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, halfDuplex) },
|
||||||
#if defined(TELEMETRY_FRSKY)
|
#if defined(TELEMETRY_FRSKY)
|
||||||
#if defined(GPS)
|
#if defined(USE_GPS)
|
||||||
{ "frsky_default_lat", VAR_INT16 | MASTER_VALUE, .config.minmax = { -9000, 9000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLatitude) },
|
{ "frsky_default_lat", VAR_INT16 | MASTER_VALUE, .config.minmax = { -9000, 9000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLatitude) },
|
||||||
{ "frsky_default_long", VAR_INT16 | MASTER_VALUE, .config.minmax = { -18000, 18000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLongitude) },
|
{ "frsky_default_long", VAR_INT16 | MASTER_VALUE, .config.minmax = { -18000, 18000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLongitude) },
|
||||||
{ "frsky_gps_format", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, FRSKY_FORMAT_NMEA }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_coordinate_format) },
|
{ "frsky_gps_format", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, FRSKY_FORMAT_NMEA }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_coordinate_format) },
|
||||||
|
@ -667,7 +667,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_OSD_CONFIG
|
// PG_OSD_CONFIG
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_UNIT }, PG_OSD_CONFIG, offsetof(osdConfig_t, units) },
|
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_UNIT }, PG_OSD_CONFIG, offsetof(osdConfig_t, units) },
|
||||||
{ "osd_warnings", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings) },
|
{ "osd_warnings", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, INT16_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabledWarnings) },
|
||||||
|
|
||||||
|
|
|
@ -26,11 +26,11 @@ typedef enum {
|
||||||
TABLE_OFF_ON = 0,
|
TABLE_OFF_ON = 0,
|
||||||
TABLE_UNIT,
|
TABLE_UNIT,
|
||||||
TABLE_ALIGNMENT,
|
TABLE_ALIGNMENT,
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
TABLE_GPS_PROVIDER,
|
TABLE_GPS_PROVIDER,
|
||||||
TABLE_GPS_SBAS_MODE,
|
TABLE_GPS_SBAS_MODE,
|
||||||
#endif
|
#endif
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
TABLE_BLACKBOX_DEVICE,
|
TABLE_BLACKBOX_DEVICE,
|
||||||
#endif
|
#endif
|
||||||
TABLE_CURRENT_METER,
|
TABLE_CURRENT_METER,
|
||||||
|
@ -47,10 +47,10 @@ typedef enum {
|
||||||
TABLE_GYRO_LPF,
|
TABLE_GYRO_LPF,
|
||||||
TABLE_GYRO_HARDWARE,
|
TABLE_GYRO_HARDWARE,
|
||||||
TABLE_ACC_HARDWARE,
|
TABLE_ACC_HARDWARE,
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
TABLE_BARO_HARDWARE,
|
TABLE_BARO_HARDWARE,
|
||||||
#endif
|
#endif
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
TABLE_MAG_HARDWARE,
|
TABLE_MAG_HARDWARE,
|
||||||
#endif
|
#endif
|
||||||
TABLE_DEBUG,
|
TABLE_DEBUG,
|
||||||
|
@ -61,7 +61,7 @@ typedef enum {
|
||||||
TABLE_LOWPASS_TYPE,
|
TABLE_LOWPASS_TYPE,
|
||||||
TABLE_FAILSAFE,
|
TABLE_FAILSAFE,
|
||||||
TABLE_CRASH_RECOVERY,
|
TABLE_CRASH_RECOVERY,
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
TABLE_OSD,
|
TABLE_OSD,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_CAMERA_CONTROL
|
#ifdef USE_CAMERA_CONTROL
|
||||||
|
|
|
@ -52,7 +52,7 @@ static int32_t estimatedVario = 0; // variometer in cm/s
|
||||||
static int32_t estimatedAltitude = 0; // in cm
|
static int32_t estimatedAltitude = 0; // in cm
|
||||||
|
|
||||||
|
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
|
|
||||||
enum {
|
enum {
|
||||||
DEBUG_ALTITUDE_ACC,
|
DEBUG_ALTITUDE_ACC,
|
||||||
|
@ -216,7 +216,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
|
||||||
static float accAlt = 0.0f;
|
static float accAlt = 0.0f;
|
||||||
|
|
||||||
int32_t baroAlt = 0;
|
int32_t baroAlt = 0;
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
if (!isBaroCalibrationComplete()) {
|
if (!isBaroCalibrationComplete()) {
|
||||||
performBaroCalibrationCycle();
|
performBaroCalibrationCycle();
|
||||||
|
@ -229,7 +229,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
if (sensors(SENSOR_SONAR)) {
|
if (sensors(SENSOR_SONAR)) {
|
||||||
int32_t sonarAlt = sonarCalculateAltitude(sonarRead(), getCosTiltAngle());
|
int32_t sonarAlt = sonarCalculateAltitude(sonarRead(), getCosTiltAngle());
|
||||||
if (sonarAlt > 0 && sonarAlt >= sonarCfAltCm && sonarAlt <= sonarMaxAltWithTiltCm) {
|
if (sonarAlt > 0 && sonarAlt >= sonarCfAltCm && sonarAlt <= sonarMaxAltWithTiltCm) {
|
||||||
|
@ -242,7 +242,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
float accZ_tmp = 0;
|
float accZ_tmp = 0;
|
||||||
#ifdef ACC
|
#ifdef USE_ACC
|
||||||
if (sensors(SENSOR_ACC)) {
|
if (sensors(SENSOR_ACC)) {
|
||||||
const float dt = accTimeSum * 1e-6f; // delta acc reading time in seconds
|
const float dt = accTimeSum * 1e-6f; // delta acc reading time in seconds
|
||||||
|
|
||||||
|
@ -267,7 +267,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
|
||||||
imuResetAccelerationSum();
|
imuResetAccelerationSum();
|
||||||
|
|
||||||
int32_t baroVel = 0;
|
int32_t baroVel = 0;
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
if (sensors(SENSOR_BARO)) {
|
if (sensors(SENSOR_BARO)) {
|
||||||
if (!isBaroCalibrationComplete()) {
|
if (!isBaroCalibrationComplete()) {
|
||||||
return;
|
return;
|
||||||
|
@ -294,7 +294,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
|
||||||
altHoldThrottleAdjustment = calculateAltHoldThrottleAdjustment(vel_tmp, accZ_tmp, accZ_old);
|
altHoldThrottleAdjustment = calculateAltHoldThrottleAdjustment(vel_tmp, accZ_tmp, accZ_old);
|
||||||
accZ_old = accZ_tmp;
|
accZ_old = accZ_tmp;
|
||||||
}
|
}
|
||||||
#endif // defined(BARO) || defined(SONAR)
|
#endif // defined(USE_BARO) || defined(USE_SONAR)
|
||||||
|
|
||||||
int32_t getEstimatedAltitude(void)
|
int32_t getEstimatedAltitude(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -423,7 +423,7 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
|
||||||
if (sensors(SENSOR_MAG) && isMagnetometerHealthy()) {
|
if (sensors(SENSOR_MAG) && isMagnetometerHealthy()) {
|
||||||
useMag = true;
|
useMag = true;
|
||||||
}
|
}
|
||||||
#if defined(GPS)
|
#if defined(USE_GPS)
|
||||||
else if (STATE(FIXED_WING) && sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5 && gpsSol.groundSpeed >= 300) {
|
else if (STATE(FIXED_WING) && sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5 && gpsSol.groundSpeed >= 300) {
|
||||||
// In case of a fixed-wing aircraft we can use GPS course over ground to correct heading
|
// In case of a fixed-wing aircraft we can use GPS course over ground to correct heading
|
||||||
rawYawError = DECIDEGREES_TO_RADIANS(attitude.values.yaw - gpsSol.groundCourse);
|
rawYawError = DECIDEGREES_TO_RADIANS(attitude.values.yaw - gpsSol.groundCourse);
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
|
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
|
|
@ -371,7 +371,7 @@ static float pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPit
|
||||||
// calculate error angle and limit the angle to the max inclination
|
// calculate error angle and limit the angle to the max inclination
|
||||||
// rcDeflection is in range [-1.0, 1.0]
|
// rcDeflection is in range [-1.0, 1.0]
|
||||||
float angle = pidProfile->levelAngleLimit * getRcDeflection(axis);
|
float angle = pidProfile->levelAngleLimit * getRcDeflection(axis);
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
angle += GPS_angle[axis];
|
angle += GPS_angle[axis];
|
||||||
#endif
|
#endif
|
||||||
angle = constrainf(angle, -pidProfile->levelAngleLimit, pidProfile->levelAngleLimit);
|
angle = constrainf(angle, -pidProfile->levelAngleLimit, pidProfile->levelAngleLimit);
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
#include "io/statusindicator.h"
|
#include "io/statusindicator.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -331,7 +331,7 @@ void beeperWarningBeeps(uint8_t beepCount)
|
||||||
beeper(BEEPER_MULTI_BEEPS);
|
beeper(BEEPER_MULTI_BEEPS);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void beeperGpsStatus(void)
|
static void beeperGpsStatus(void)
|
||||||
{
|
{
|
||||||
if (!(getBeeperOffMask() & (1 << (BEEPER_GPS_STATUS - 1)))) {
|
if (!(getBeeperOffMask() & (1 << (BEEPER_GPS_STATUS - 1)))) {
|
||||||
|
@ -361,7 +361,7 @@ void beeperUpdate(timeUs_t currentTimeUs)
|
||||||
// If beeper option from AUX switch has been selected
|
// If beeper option from AUX switch has been selected
|
||||||
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) {
|
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) {
|
||||||
beeper(BEEPER_RX_SET);
|
beeper(BEEPER_RX_SET);
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
} else if (feature(FEATURE_GPS) && IS_RC_MODE_ACTIVE(BOXBEEPGPSCOUNT)) {
|
} else if (feature(FEATURE_GPS) && IS_RC_MODE_ACTIVE(BOXBEEPGPSCOUNT)) {
|
||||||
beeperGpsStatus();
|
beeperGpsStatus();
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -148,7 +148,7 @@ static void padLineBuffer(void)
|
||||||
lineBuffer[length] = 0;
|
lineBuffer[length] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void padHalfLineBuffer(void)
|
static void padHalfLineBuffer(void)
|
||||||
{
|
{
|
||||||
uint8_t halfLineIndex = sizeof(lineBuffer) / 2;
|
uint8_t halfLineIndex = sizeof(lineBuffer) / 2;
|
||||||
|
@ -345,7 +345,7 @@ static void showProfilePage(void)
|
||||||
#define SATELLITE_COUNT (sizeof(GPS_svinfo_cno) / sizeof(GPS_svinfo_cno[0]))
|
#define SATELLITE_COUNT (sizeof(GPS_svinfo_cno) / sizeof(GPS_svinfo_cno[0]))
|
||||||
#define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2)
|
#define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2)
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void showGpsPage(void)
|
static void showGpsPage(void)
|
||||||
{
|
{
|
||||||
if (!feature(FEATURE_GPS)) {
|
if (!feature(FEATURE_GPS)) {
|
||||||
|
@ -489,7 +489,7 @@ static void showSensorsPage(void)
|
||||||
i2c_OLED_send_string(bus, lineBuffer);
|
i2c_OLED_send_string(bus, lineBuffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
if (sensors(SENSOR_MAG)) {
|
if (sensors(SENSOR_MAG)) {
|
||||||
tfp_sprintf(lineBuffer, format, "MAG", mag.magADC[X], mag.magADC[Y], mag.magADC[Z]);
|
tfp_sprintf(lineBuffer, format, "MAG", mag.magADC[X], mag.magADC[Y], mag.magADC[Z]);
|
||||||
padLineBuffer();
|
padLineBuffer();
|
||||||
|
@ -575,7 +575,7 @@ static const pageEntry_t pages[PAGE_COUNT] = {
|
||||||
{ PAGE_WELCOME, FC_FIRMWARE_NAME, showWelcomePage, PAGE_FLAGS_SKIP_CYCLING },
|
{ PAGE_WELCOME, FC_FIRMWARE_NAME, showWelcomePage, PAGE_FLAGS_SKIP_CYCLING },
|
||||||
{ PAGE_ARMED, "ARMED", showArmedPage, PAGE_FLAGS_SKIP_CYCLING },
|
{ PAGE_ARMED, "ARMED", showArmedPage, PAGE_FLAGS_SKIP_CYCLING },
|
||||||
{ PAGE_PROFILE, "PROFILE", showProfilePage, PAGE_FLAGS_NONE },
|
{ PAGE_PROFILE, "PROFILE", showProfilePage, PAGE_FLAGS_NONE },
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
{ PAGE_GPS, "GPS", showGpsPage, PAGE_FLAGS_NONE },
|
{ PAGE_GPS, "GPS", showGpsPage, PAGE_FLAGS_NONE },
|
||||||
#endif
|
#endif
|
||||||
{ PAGE_RX, "RX", showRxPage, PAGE_FLAGS_NONE },
|
{ PAGE_RX, "RX", showRxPage, PAGE_FLAGS_NONE },
|
||||||
|
@ -605,7 +605,7 @@ void dashboardUpdate(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
static uint8_t previousArmedState = 0;
|
static uint8_t previousArmedState = 0;
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
if (displayIsGrabbed(displayPort)) {
|
if (displayIsGrabbed(displayPort)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -686,7 +686,7 @@ void dashboardInit(void)
|
||||||
delay(200);
|
delay(200);
|
||||||
|
|
||||||
displayPort = displayPortOledInit(bus);
|
displayPort = displayPortOledInit(bus);
|
||||||
#if defined(CMS)
|
#if defined(USE_CMS)
|
||||||
if (dashboardPresent) {
|
if (dashboardPresent) {
|
||||||
cmsDisplayPortRegister(displayPort);
|
cmsDisplayPortRegister(displayPort);
|
||||||
}
|
}
|
||||||
|
|
|
@ -48,7 +48,7 @@ typedef enum {
|
||||||
#ifndef SKIP_TASK_STATISTICS
|
#ifndef SKIP_TASK_STATISTICS
|
||||||
PAGE_TASKS,
|
PAGE_TASKS,
|
||||||
#endif
|
#endif
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
PAGE_GPS,
|
PAGE_GPS,
|
||||||
#endif
|
#endif
|
||||||
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
|
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
|
||||||
|
|
|
@ -54,7 +54,7 @@ static int grab(displayPort_t *displayPort)
|
||||||
{
|
{
|
||||||
// FIXME this should probably not have a dependency on the OSD or OSD slave code
|
// FIXME this should probably not have a dependency on the OSD or OSD slave code
|
||||||
UNUSED(displayPort);
|
UNUSED(displayPort);
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
osdResetAlarms();
|
osdResetAlarms();
|
||||||
resumeRefreshAt = 0;
|
resumeRefreshAt = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
|
@ -430,10 +430,10 @@ static const struct {
|
||||||
uint8_t ledMode;
|
uint8_t ledMode;
|
||||||
} flightModeToLed[] = {
|
} flightModeToLed[] = {
|
||||||
{HEADFREE_MODE, LED_MODE_HEADFREE},
|
{HEADFREE_MODE, LED_MODE_HEADFREE},
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
{MAG_MODE, LED_MODE_MAG},
|
{MAG_MODE, LED_MODE_MAG},
|
||||||
#endif
|
#endif
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
{BARO_MODE, LED_MODE_BARO},
|
{BARO_MODE, LED_MODE_BARO},
|
||||||
#endif
|
#endif
|
||||||
{HORIZON_MODE, LED_MODE_HORIZON},
|
{HORIZON_MODE, LED_MODE_HORIZON},
|
||||||
|
@ -735,7 +735,7 @@ static void applyLedRssiLayer(bool updateNow, timeUs_t *timer)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void applyLedGpsLayer(bool updateNow, timeUs_t *timer)
|
static void applyLedGpsLayer(bool updateNow, timeUs_t *timer)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
@ -996,7 +996,7 @@ typedef enum {
|
||||||
timLarson,
|
timLarson,
|
||||||
timBattery,
|
timBattery,
|
||||||
timRssi,
|
timRssi,
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
timGps,
|
timGps,
|
||||||
#endif
|
#endif
|
||||||
timWarning,
|
timWarning,
|
||||||
|
@ -1025,7 +1025,7 @@ static applyLayerFn_timed* layerTable[] = {
|
||||||
[timLarson] = &applyLarsonScannerLayer,
|
[timLarson] = &applyLarsonScannerLayer,
|
||||||
[timBattery] = &applyLedBatteryLayer,
|
[timBattery] = &applyLedBatteryLayer,
|
||||||
[timRssi] = &applyLedRssiLayer,
|
[timRssi] = &applyLedRssiLayer,
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
[timGps] = &applyLedGpsLayer,
|
[timGps] = &applyLedGpsLayer,
|
||||||
#endif
|
#endif
|
||||||
[timWarning] = &applyLedWarningLayer,
|
[timWarning] = &applyLedWarningLayer,
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
|
|
||||||
#include "blackbox/blackbox.h"
|
#include "blackbox/blackbox.h"
|
||||||
#include "blackbox/blackbox_io.h"
|
#include "blackbox/blackbox_io.h"
|
||||||
|
@ -346,7 +346,7 @@ static void osdDrawSingleElement(uint8_t item)
|
||||||
tfp_sprintf(buff, "%4d%c", getMAhDrawn(), SYM_MAH);
|
tfp_sprintf(buff, "%4d%c", getMAhDrawn(), SYM_MAH);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
case OSD_GPS_SATS:
|
case OSD_GPS_SATS:
|
||||||
tfp_sprintf(buff, "%c%c%d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat);
|
tfp_sprintf(buff, "%c%c%d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat);
|
||||||
break;
|
break;
|
||||||
|
@ -769,7 +769,7 @@ static void osdDrawElements(void)
|
||||||
osdDrawSingleElement(OSD_NUMERICAL_VARIO);
|
osdDrawSingleElement(OSD_NUMERICAL_VARIO);
|
||||||
osdDrawSingleElement(OSD_COMPASS_BAR);
|
osdDrawSingleElement(OSD_COMPASS_BAR);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (sensors(SENSOR_GPS)) {
|
if (sensors(SENSOR_GPS)) {
|
||||||
osdDrawSingleElement(OSD_GPS_SATS);
|
osdDrawSingleElement(OSD_GPS_SATS);
|
||||||
osdDrawSingleElement(OSD_GPS_SPEED);
|
osdDrawSingleElement(OSD_GPS_SPEED);
|
||||||
|
@ -847,7 +847,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
|
||||||
BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31,31));
|
BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31,31));
|
||||||
|
|
||||||
osdDisplayPort = osdDisplayPortToUse;
|
osdDisplayPort = osdDisplayPortToUse;
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
cmsDisplayPortRegister(osdDisplayPort);
|
cmsDisplayPortRegister(osdDisplayPort);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -862,7 +862,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
|
||||||
char string_buffer[30];
|
char string_buffer[30];
|
||||||
tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING);
|
tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING);
|
||||||
displayWrite(osdDisplayPort, 20, 6, string_buffer);
|
displayWrite(osdDisplayPort, 20, 6, string_buffer);
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1);
|
displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1);
|
||||||
displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT2);
|
displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT2);
|
||||||
displayWrite(osdDisplayPort, 11, 10, CMS_STARTUP_HELP_TEXT3);
|
displayWrite(osdDisplayPort, 11, 10, CMS_STARTUP_HELP_TEXT3);
|
||||||
|
@ -952,7 +952,7 @@ static void osdResetStats(void)
|
||||||
static void osdUpdateStats(void)
|
static void osdUpdateStats(void)
|
||||||
{
|
{
|
||||||
int16_t value = 0;
|
int16_t value = 0;
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
value = CM_S_TO_KM_H(gpsSol.groundSpeed);
|
value = CM_S_TO_KM_H(gpsSol.groundSpeed);
|
||||||
#endif
|
#endif
|
||||||
if (stats.max_speed < value)
|
if (stats.max_speed < value)
|
||||||
|
@ -971,14 +971,14 @@ static void osdUpdateStats(void)
|
||||||
if (stats.max_altitude < getEstimatedAltitude())
|
if (stats.max_altitude < getEstimatedAltitude())
|
||||||
stats.max_altitude = getEstimatedAltitude();
|
stats.max_altitude = getEstimatedAltitude();
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && (stats.max_distance < GPS_distanceToHome)) {
|
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && (stats.max_distance < GPS_distanceToHome)) {
|
||||||
stats.max_distance = GPS_distanceToHome;
|
stats.max_distance = GPS_distanceToHome;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
static void osdGetBlackboxStatusString(char * buff)
|
static void osdGetBlackboxStatusString(char * buff)
|
||||||
{
|
{
|
||||||
bool storageDeviceIsWorking = false;
|
bool storageDeviceIsWorking = false;
|
||||||
|
@ -1101,7 +1101,7 @@ static void osdShowStats(void)
|
||||||
osdDisplayStatisticLabel(top++, "MAX ALTITUDE", buff);
|
osdDisplayStatisticLabel(top++, "MAX ALTITUDE", buff);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
if (osdConfig()->enabled_stats[OSD_STAT_BLACKBOX] && blackboxConfig()->device && blackboxConfig()->device != BLACKBOX_DEVICE_SERIAL) {
|
if (osdConfig()->enabled_stats[OSD_STAT_BLACKBOX] && blackboxConfig()->device && blackboxConfig()->device != BLACKBOX_DEVICE_SERIAL) {
|
||||||
osdGetBlackboxStatusString(buff);
|
osdGetBlackboxStatusString(buff);
|
||||||
osdDisplayStatisticLabel(top++, "BLACKBOX", buff);
|
osdDisplayStatisticLabel(top++, "BLACKBOX", buff);
|
||||||
|
@ -1175,7 +1175,7 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
if (!displayIsGrabbed(osdDisplayPort)) {
|
if (!displayIsGrabbed(osdDisplayPort)) {
|
||||||
osdUpdateAlarms();
|
osdUpdateAlarms();
|
||||||
osdDrawElements();
|
osdDrawElements();
|
||||||
|
@ -1230,7 +1230,7 @@ void osdUpdate(timeUs_t currentTimeUs)
|
||||||
displayDrawScreen(osdDisplayPort);
|
displayDrawScreen(osdDisplayPort);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
// do not allow ARM if we are in menu
|
// do not allow ARM if we are in menu
|
||||||
if (displayIsGrabbed(osdDisplayPort)) {
|
if (displayIsGrabbed(osdDisplayPort)) {
|
||||||
setArmingDisabled(ARMING_DISABLED_OSD_MENU);
|
setArmingDisabled(ARMING_DISABLED_OSD_MENU);
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
|
|
||||||
|
|
|
@ -195,7 +195,7 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
UNUSED(currentTimeUs);
|
UNUSED(currentTimeUs);
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
if (cmsInMenu) {
|
if (cmsInMenu) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -514,7 +514,7 @@ void serialEvaluateNonMspData(serialPort_t *serialPort, uint8_t receivedChar)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH)
|
#if defined(USE_GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH)
|
||||||
// Default data consumer for serialPassThrough.
|
// Default data consumer for serialPassThrough.
|
||||||
static void nopConsumer(uint8_t data)
|
static void nopConsumer(uint8_t data)
|
||||||
{
|
{
|
||||||
|
|
|
@ -52,7 +52,7 @@ bool canUpdateVTX(void);
|
||||||
|
|
||||||
#define WAIT_FOR_VTX while (!canUpdateVTX()) {}
|
#define WAIT_FOR_VTX while (!canUpdateVTX()) {}
|
||||||
|
|
||||||
#if defined(CMS) || defined(VTX_COMMON)
|
#if defined(USE_CMS) || defined(VTX_COMMON)
|
||||||
const char * const rtc6705PowerNames[VTX_RTC6705_POWER_COUNT] = {
|
const char * const rtc6705PowerNames[VTX_RTC6705_POWER_COUNT] = {
|
||||||
"---", "25 ", "200",
|
"---", "25 ", "200",
|
||||||
};
|
};
|
||||||
|
|
|
@ -64,7 +64,7 @@ serialPort_t *debugSerialPort = NULL;
|
||||||
|
|
||||||
static serialPort_t *smartAudioSerialPort = NULL;
|
static serialPort_t *smartAudioSerialPort = NULL;
|
||||||
|
|
||||||
#if defined(CMS) || defined(VTX_COMMON)
|
#if defined(USE_CMS) || defined(VTX_COMMON)
|
||||||
static const char * const saPowerNames[VTX_SMARTAUDIO_POWER_COUNT+1] = {
|
static const char * const saPowerNames[VTX_SMARTAUDIO_POWER_COUNT+1] = {
|
||||||
"---", "25 ", "200", "500", "800",
|
"---", "25 ", "200", "500", "800",
|
||||||
};
|
};
|
||||||
|
@ -349,7 +349,7 @@ static void saProcessResponse(uint8_t *buf, int len)
|
||||||
// Todo: Update states in saVtxDevice?
|
// Todo: Update states in saVtxDevice?
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
// Export current device status for CMS
|
// Export current device status for CMS
|
||||||
saCmsUpdate();
|
saCmsUpdate();
|
||||||
saUpdateStatusString();
|
saUpdateStatusString();
|
||||||
|
|
|
@ -112,7 +112,7 @@ extern serialPort_t *debugSerialPort;
|
||||||
#endif // SMARTAUDIO_DPRINTF
|
#endif // SMARTAUDIO_DPRINTF
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
|
|
||||||
uint16_t smartAudioSmartbaud;
|
uint16_t smartAudioSmartbaud;
|
||||||
|
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
#include "io/vtx_string.h"
|
#include "io/vtx_string.h"
|
||||||
|
|
||||||
#if defined(CMS) || defined(VTX_COMMON)
|
#if defined(USE_CMS) || defined(VTX_COMMON)
|
||||||
const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
|
const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
|
||||||
25, 100, 200, 400, 600
|
25, 100, 200, 400, 600
|
||||||
};
|
};
|
||||||
|
@ -519,7 +519,7 @@ void vtxTrampProcess(uint32_t currentTimeUs)
|
||||||
debug[3] = 0;
|
debug[3] = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
trampCmsUpdateStatusString();
|
trampCmsUpdateStatusString();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -62,19 +62,19 @@ typedef enum {
|
||||||
#ifdef BEEPER
|
#ifdef BEEPER
|
||||||
TASK_BEEPER,
|
TASK_BEEPER,
|
||||||
#endif
|
#endif
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
TASK_GPS,
|
TASK_GPS,
|
||||||
#endif
|
#endif
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
TASK_COMPASS,
|
TASK_COMPASS,
|
||||||
#endif
|
#endif
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
TASK_BARO,
|
TASK_BARO,
|
||||||
#endif
|
#endif
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
TASK_SONAR,
|
TASK_SONAR,
|
||||||
#endif
|
#endif
|
||||||
#if defined(BARO) || defined(SONAR)
|
#if defined(USE_BARO) || defined(USE_SONAR)
|
||||||
TASK_ALTITUDE,
|
TASK_ALTITUDE,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_DASHBOARD
|
#ifdef USE_DASHBOARD
|
||||||
|
@ -92,7 +92,7 @@ typedef enum {
|
||||||
#ifdef STACK_CHECK
|
#ifdef STACK_CHECK
|
||||||
TASK_STACK_CHECK,
|
TASK_STACK_CHECK,
|
||||||
#endif
|
#endif
|
||||||
#ifdef OSD
|
#ifdef USE_OSD
|
||||||
TASK_OSD,
|
TASK_OSD,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_OSD_SLAVE
|
#ifdef USE_OSD_SLAVE
|
||||||
|
@ -104,7 +104,7 @@ typedef enum {
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
TASK_ESC_SENSOR,
|
TASK_ESC_SENSOR,
|
||||||
#endif
|
#endif
|
||||||
#ifdef CMS
|
#ifdef USE_CMS
|
||||||
TASK_CMS,
|
TASK_CMS,
|
||||||
#endif
|
#endif
|
||||||
#ifdef VTX_CONTROL
|
#ifdef VTX_CONTROL
|
||||||
|
|
|
@ -111,7 +111,7 @@ void pgResetFn_barometerConfig(barometerConfig_t *barometerConfig)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
|
|
||||||
static uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
|
static uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
|
||||||
static int32_t baroPressure = 0;
|
static int32_t baroPressure = 0;
|
||||||
|
|
|
@ -106,7 +106,7 @@ void pgResetFn_compassConfig(compassConfig_t *compassConfig)
|
||||||
compassConfig->interruptTag = COMPASS_INTERRUPT_TAG;
|
compassConfig->interruptTag = COMPASS_INTERRUPT_TAG;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(MAG)
|
#if defined(USE_MAG)
|
||||||
|
|
||||||
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
||||||
static uint8_t magInit = 0;
|
static uint8_t magInit = 0;
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE };
|
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE };
|
||||||
|
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
static bool sonarDetect(void)
|
static bool sonarDetect(void)
|
||||||
{
|
{
|
||||||
if (feature(FEATURE_SONAR)) {
|
if (feature(FEATURE_SONAR)) {
|
||||||
|
@ -65,15 +65,15 @@ bool sensorsAutodetect(void)
|
||||||
accInit(gyro.targetLooptime);
|
accInit(gyro.targetLooptime);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef MAG
|
#ifdef USE_MAG
|
||||||
compassInit();
|
compassInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef USE_BARO
|
||||||
baroDetect(&baro.dev, barometerConfig()->baro_hardware);
|
baroDetect(&baro.dev, barometerConfig()->baro_hardware);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
if (sonarDetect()) {
|
if (sonarDetect()) {
|
||||||
sonarInit(sonarConfig());
|
sonarInit(sonarConfig());
|
||||||
}
|
}
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef USE_SONAR
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
|
|
@ -31,8 +31,8 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
//#define ENSURE_MPU_DATA_READY_IS_LOW
|
//#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
|
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define GYRO_MPU6050_ALIGN CW180_DEG
|
#define GYRO_MPU6050_ALIGN CW180_DEG
|
||||||
|
@ -48,10 +48,10 @@
|
||||||
#define MPU6000_CS_PIN PB12
|
#define MPU6000_CS_PIN PB12
|
||||||
#define MPU6000_SPI_INSTANCE SPI2
|
#define MPU6000_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
//#define BARO
|
//#define USE_BARO
|
||||||
//#define USE_BARO_MS5611
|
//#define USE_BARO_MS5611
|
||||||
|
|
||||||
//#define MAG
|
//#define USE_MAG
|
||||||
//#define USE_MAG_HMC5883
|
//#define USE_MAG_HMC5883
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
|
@ -39,15 +39,15 @@
|
||||||
#define MPU6500_CS_PIN PB12
|
#define MPU6500_CS_PIN PB12
|
||||||
#define MPU6500_SPI_INSTANCE SPI2
|
#define MPU6500_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW0_DEG
|
#define GYRO_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW0_DEG
|
#define ACC_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_SPI_BMP280
|
#define USE_BARO_SPI_BMP280
|
||||||
|
|
||||||
#define BMP280_SPI_INSTANCE SPI2
|
#define BMP280_SPI_INSTANCE SPI2
|
||||||
|
|
|
@ -32,12 +32,12 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
|
|
||||||
#define GYRO_MPU6050_ALIGN CW0_DEG
|
#define GYRO_MPU6050_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
|
|
||||||
#define ACC_MPU6050_ALIGN CW0_DEG
|
#define ACC_MPU6050_ALIGN CW0_DEG
|
||||||
|
|
|
@ -42,14 +42,14 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
// Using MPU6050 for the moment.
|
// Using MPU6050 for the moment.
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
||||||
#define GYRO_MPU6050_ALIGN CW270_DEG
|
#define GYRO_MPU6050_ALIGN CW270_DEG
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
|
|
||||||
|
@ -57,11 +57,11 @@
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
// No baro support.
|
// No baro support.
|
||||||
//#define BARO
|
//#define USE_BARO
|
||||||
//#define USE_BARO_MS5611
|
//#define USE_BARO_MS5611
|
||||||
|
|
||||||
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
|
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
|
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
|
||||||
|
|
||||||
|
|
|
@ -43,22 +43,22 @@
|
||||||
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
|
|
||||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||||
#define MAG_AK8963_ALIGN CW270_DEG
|
#define MAG_AK8963_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
|
|
||||||
|
|
|
@ -41,15 +41,15 @@
|
||||||
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define USE_MAG_SPI_HMC5883
|
#define USE_MAG_SPI_HMC5883
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
|
@ -64,7 +64,7 @@
|
||||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||||
#define MAG_AK8963_ALIGN CW270_DEG
|
#define MAG_AK8963_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
#define USE_BARO_SPI_MS5611
|
#define USE_BARO_SPI_MS5611
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
|
|
|
@ -105,7 +105,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* OSD MAX7456E */
|
/* OSD MAX7456E */
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
|
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI2
|
#define MAX7456_SPI_INSTANCE SPI2
|
||||||
|
@ -124,17 +124,17 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
// MAG
|
// MAG
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
#define MAG_AK8963_ALIGN CW0_DEG
|
#define MAG_AK8963_ALIGN CW0_DEG
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
// GYRO
|
// GYRO
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW0_DEG
|
#define GYRO_MPU6500_ALIGN CW0_DEG
|
||||||
// ACC
|
// ACC
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW0_DEG
|
#define ACC_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
|
@ -142,7 +142,7 @@
|
||||||
* TODO: not implemented on V1 or V2 pcb
|
* TODO: not implemented on V1 or V2 pcb
|
||||||
*/
|
*/
|
||||||
#if defined(BREADBOARD)
|
#if defined(BREADBOARD)
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
#define USE_BARO_SPI_BMP280
|
#define USE_BARO_SPI_BMP280
|
||||||
#define BMP280_SPI_INSTANCE SPI3
|
#define BMP280_SPI_INSTANCE SPI3
|
||||||
|
@ -211,7 +211,7 @@
|
||||||
/* OLED Support
|
/* OLED Support
|
||||||
*/
|
*/
|
||||||
#if defined(BREADBOARD)
|
#if defined(BREADBOARD)
|
||||||
#define CMS
|
#define USE_CMS
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define USE_I2C_DEVICE_1
|
#define USE_I2C_DEVICE_1
|
||||||
#define I2C_DEVICE (I2CDEV_1)
|
#define I2C_DEVICE (I2CDEV_1)
|
||||||
|
|
|
@ -30,11 +30,11 @@
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
@ -43,14 +43,14 @@
|
||||||
#define MPU_INT_EXTI PC4
|
#define MPU_INT_EXTI PC4
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define MAG_I2C_INSTANCE (I2CDEV_2)
|
#define MAG_I2C_INSTANCE (I2CDEV_2)
|
||||||
|
|
||||||
//#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
//#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
||||||
//#define MAG_HMC5883_ALIGN CW90_DEG
|
//#define MAG_HMC5883_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
#define BARO_I2C_INSTANCE (I2CDEV_2)
|
#define BARO_I2C_INSTANCE (I2CDEV_2)
|
||||||
|
@ -120,7 +120,7 @@
|
||||||
#define SPI4_MISO_PIN PE13
|
#define SPI4_MISO_PIN PE13
|
||||||
#define SPI4_MOSI_PIN PE14
|
#define SPI4_MOSI_PIN PE14
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN
|
#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN
|
||||||
|
|
|
@ -32,11 +32,11 @@
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
@ -45,13 +45,13 @@
|
||||||
#define MPU_INT_EXTI PC4
|
#define MPU_INT_EXTI PC4
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
//#define USE_MAG_HMC5883
|
//#define USE_MAG_HMC5883
|
||||||
//#define HMC5883_BUS I2C_DEVICE_EXT
|
//#define HMC5883_BUS I2C_DEVICE_EXT
|
||||||
//#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
//#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
||||||
//#define MAG_HMC5883_ALIGN CW90_DEG
|
//#define MAG_HMC5883_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 16
|
#define USABLE_TIMER_CHANNEL_COUNT 16
|
||||||
|
@ -117,7 +117,7 @@
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN
|
#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN
|
||||||
|
|
|
@ -31,11 +31,11 @@
|
||||||
#define MPU_INT_EXTI PB6
|
#define MPU_INT_EXTI PB6
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
@ -76,7 +76,7 @@
|
||||||
#define MPU6500_CS_PIN PA15
|
#define MPU6500_CS_PIN PA15
|
||||||
#define MPU6500_SPI_INSTANCE SPI3
|
#define MPU6500_SPI_INSTANCE SPI3
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI1
|
#define MAX7456_SPI_INSTANCE SPI1
|
||||||
#define MAX7456_SPI_CS_PIN PA4
|
#define MAX7456_SPI_CS_PIN PA4
|
||||||
|
|
|
@ -35,18 +35,18 @@
|
||||||
#define ICM20689_CS_PIN SPI1_NSS_PIN
|
#define ICM20689_CS_PIN SPI1_NSS_PIN
|
||||||
#define ICM20689_SPI_INSTANCE SPI1
|
#define ICM20689_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW270_DEG
|
#define ACC_ICM20689_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW270_DEG
|
#define GYRO_ICM20689_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN
|
#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN
|
||||||
|
|
|
@ -30,11 +30,11 @@
|
||||||
#define MPU6000_CS_PIN PA15
|
#define MPU6000_CS_PIN PA15
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -87,7 +87,7 @@
|
||||||
#define SPI2_MISO_PIN PB14
|
#define SPI2_MISO_PIN PB14
|
||||||
#define SPI2_MOSI_PIN PB15
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
// include the max7456 driver
|
// include the max7456 driver
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI1
|
#define MAX7456_SPI_INSTANCE SPI1
|
||||||
|
|
|
@ -33,11 +33,11 @@
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -48,13 +48,13 @@
|
||||||
#define MPU_INT_EXTI PC4
|
#define MPU_INT_EXTI PC4
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_SPI_BMP280
|
#define USE_BARO_SPI_BMP280
|
||||||
|
|
||||||
#define BMP280_SPI_INSTANCE SPI2
|
#define BMP280_SPI_INSTANCE SPI2
|
||||||
#define BMP280_CS_PIN PB3
|
#define BMP280_CS_PIN PB3
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI2
|
#define MAX7456_SPI_INSTANCE SPI2
|
||||||
#define MAX7456_SPI_CS_PIN PB12
|
#define MAX7456_SPI_CS_PIN PB12
|
||||||
|
|
|
@ -50,22 +50,22 @@
|
||||||
#define MPU6500_CS_PIN PC4
|
#define MPU6500_CS_PIN PC4
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW0_DEG
|
#define ACC_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6500
|
#define USE_GYRO_MPU6500
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW0_DEG
|
#define GYRO_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
//#define USE_MAG_AK8963
|
//#define USE_MAG_AK8963
|
||||||
#define HMC5883_I2C_INSTANCE I2CDEV_1
|
#define HMC5883_I2C_INSTANCE I2CDEV_1
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
#define MS5611_I2C_INSTANCE I2CDEV_1
|
#define MS5611_I2C_INSTANCE I2CDEV_1
|
||||||
|
|
||||||
|
|
|
@ -46,11 +46,11 @@
|
||||||
#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
@ -61,13 +61,13 @@
|
||||||
//#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
|
//#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
|
||||||
|
|
||||||
// External I2C BARO
|
// External I2C BARO
|
||||||
//#define BARO
|
//#define USE_BARO
|
||||||
//#define USE_BARO_MS5611
|
//#define USE_BARO_MS5611
|
||||||
//#define USE_BARO_BMP085
|
//#define USE_BARO_BMP085
|
||||||
//#define USE_BARO_BMP280
|
//#define USE_BARO_BMP280
|
||||||
|
|
||||||
// External I2C MAG
|
// External I2C MAG
|
||||||
//#define MAG
|
//#define USE_MAG
|
||||||
//#define USE_MAG_HMC5883
|
//#define USE_MAG_HMC5883
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
@ -97,7 +97,7 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
//#define SONAR
|
//#define USE_SONAR
|
||||||
//#define SONAR_ECHO_PIN PB0
|
//#define SONAR_ECHO_PIN PB0
|
||||||
//#define SONAR_TRIGGER_PIN PB5
|
//#define SONAR_TRIGGER_PIN PB5
|
||||||
|
|
||||||
|
|
|
@ -63,7 +63,7 @@
|
||||||
//#define M25P16_CS_PIN GPIO_Pin_12
|
//#define M25P16_CS_PIN GPIO_Pin_12
|
||||||
//#define M25P16_SPI_INSTANCE SPI2
|
//#define M25P16_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_L3GD20
|
#define USE_GYRO_L3GD20
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
|
|
||||||
|
@ -75,7 +75,7 @@
|
||||||
#define GYRO_L3GD20_ALIGN CW270_DEG
|
#define GYRO_L3GD20_ALIGN CW270_DEG
|
||||||
#define GYRO_MPU6050_ALIGN CW0_DEG
|
#define GYRO_MPU6050_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
#define USE_ACC_LSM303DLHC
|
#define USE_ACC_LSM303DLHC
|
||||||
#define LSM303DLHC_I2C I2C1
|
#define LSM303DLHC_I2C I2C1
|
||||||
|
@ -87,10 +87,10 @@
|
||||||
|
|
||||||
#define ACC_MPU6050_ALIGN CW0_DEG
|
#define ACC_MPU6050_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_AK8975
|
#define USE_MAG_AK8975
|
||||||
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
||||||
|
|
||||||
|
|
|
@ -27,13 +27,13 @@
|
||||||
|
|
||||||
#undef BEEPER
|
#undef BEEPER
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
|
|
||||||
//#define MAG
|
//#define USE_MAG
|
||||||
//#define USE_MAG_HMC5883
|
//#define USE_MAG_HMC5883
|
||||||
|
|
||||||
#define BRUSHED_MOTORS
|
#define BRUSHED_MOTORS
|
||||||
|
|
|
@ -40,9 +40,9 @@
|
||||||
// MPU 6000
|
// MPU 6000
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW0_DEG
|
#define GYRO_MPU6000_ALIGN CW0_DEG
|
||||||
#define ACC_MPU6000_ALIGN CW0_DEG
|
#define ACC_MPU6000_ALIGN CW0_DEG
|
||||||
|
@ -59,7 +59,7 @@
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN PA15
|
#define MAX7456_SPI_CS_PIN PA15
|
||||||
|
|
|
@ -33,17 +33,17 @@
|
||||||
//ICM20689
|
//ICM20689
|
||||||
#define ICM20689_CS_PIN PA4
|
#define ICM20689_CS_PIN PA4
|
||||||
#define ICM20689_SPI_INSTANCE SPI1
|
#define ICM20689_SPI_INSTANCE SPI1
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW0_DEG
|
#define GYRO_ICM20689_ALIGN CW0_DEG
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW0_DEG
|
#define ACC_ICM20689_ALIGN CW0_DEG
|
||||||
|
|
||||||
//MPU-6000
|
//MPU-6000
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
|
|
||||||
#define GYRO_MPU6000_ALIGN CW0_DEG
|
#define GYRO_MPU6000_ALIGN CW0_DEG
|
||||||
|
@ -62,7 +62,7 @@
|
||||||
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
#define MPU6500_CS_PIN SPI1_NSS_PIN
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN PA15
|
#define MAX7456_SPI_CS_PIN PA15
|
||||||
|
|
|
@ -36,11 +36,11 @@
|
||||||
#define MPU6000_CS_PIN PC4
|
#define MPU6000_CS_PIN PC4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG_FLIP
|
#define ACC_MPU6000_ALIGN CW270_DEG_FLIP
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG_FLIP
|
#define GYRO_MPU6000_ALIGN CW270_DEG_FLIP
|
||||||
|
|
||||||
|
@ -49,7 +49,7 @@
|
||||||
#define MPU_INT_EXTI PC0
|
#define MPU_INT_EXTI PC0
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
||||||
|
|
||||||
|
@ -57,7 +57,7 @@
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#define M25P16_CS_PIN PB12
|
#define M25P16_CS_PIN PB12
|
||||||
|
|
|
@ -374,7 +374,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
|
|
||||||
bstWrite16(failsafeConfig()->failsafe_throttle);
|
bstWrite16(failsafeConfig()->failsafe_throttle);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
bstWrite8(gpsConfig()->provider); // gps_type
|
bstWrite8(gpsConfig()->provider); // gps_type
|
||||||
bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
|
bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
|
||||||
bstWrite8(gpsConfig()->sbasMode); // gps_ubx_sbas
|
bstWrite8(gpsConfig()->sbasMode); // gps_ubx_sbas
|
||||||
|
@ -501,7 +501,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
|
|
||||||
failsafeConfigMutable()->failsafe_throttle = bstRead16();
|
failsafeConfigMutable()->failsafe_throttle = bstRead16();
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
gpsConfigMutable()->provider = bstRead8(); // gps_type
|
gpsConfigMutable()->provider = bstRead8(); // gps_type
|
||||||
bstRead8(); // gps_baudrate
|
bstRead8(); // gps_baudrate
|
||||||
gpsConfigMutable()->sbasMode = bstRead8(); // gps_ubx_sbas
|
gpsConfigMutable()->sbasMode = bstRead8(); // gps_ubx_sbas
|
||||||
|
@ -723,7 +723,7 @@ void taskBstMasterProcess(timeUs_t currentTimeUs)
|
||||||
sendCounter = 0;
|
sendCounter = 0;
|
||||||
next20hzUpdateAt_1 = currentTimeUs + UPDATE_AT_20HZ;
|
next20hzUpdateAt_1 = currentTimeUs + UPDATE_AT_20HZ;
|
||||||
}
|
}
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
if (sensors(SENSOR_GPS) && !bstWriteBusy())
|
if (sensors(SENSOR_GPS) && !bstWriteBusy())
|
||||||
writeGpsPositionPrameToBST();
|
writeGpsPositionPrameToBST();
|
||||||
#endif
|
#endif
|
||||||
|
@ -762,7 +762,7 @@ static void bstMasterWrite16(uint16_t data)
|
||||||
/*************************************************************************************************/
|
/*************************************************************************************************/
|
||||||
#define PUBLIC_ADDRESS 0x00
|
#define PUBLIC_ADDRESS 0x00
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
static void bstMasterWrite32(uint32_t data)
|
static void bstMasterWrite32(uint32_t data)
|
||||||
{
|
{
|
||||||
bstMasterWrite16((uint8_t)(data >> 16));
|
bstMasterWrite16((uint8_t)(data >> 16));
|
||||||
|
@ -775,7 +775,7 @@ static uint16_t alt = 0;
|
||||||
static uint8_t numOfSat = 0;
|
static uint8_t numOfSat = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef USE_GPS
|
||||||
bool writeGpsPositionPrameToBST(void)
|
bool writeGpsPositionPrameToBST(void)
|
||||||
{
|
{
|
||||||
if ((lat != gpsSol.llh.lat) || (lon != gpsSol.llh.lon) || (alt != gpsSol.llh.alt) || (numOfSat != gpsSol.numSat)) {
|
if ((lat != gpsSol.llh.lat) || (lon != gpsSol.llh.lon) || (alt != gpsSol.llh.alt) || (numOfSat != gpsSol.numSat)) {
|
||||||
|
|
|
@ -53,24 +53,24 @@
|
||||||
#define MPU6000_CS_PIN SPI1_NSS_PIN
|
#define MPU6000_CS_PIN SPI1_NSS_PIN
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
#define USE_GYRO_MPU6500
|
#define USE_GYRO_MPU6500
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
#define USE_MAG_AK8975
|
#define USE_MAG_AK8975
|
||||||
|
|
|
@ -83,15 +83,15 @@
|
||||||
// address is 0x69 instead of the default 0x68
|
// address is 0x69 instead of the default 0x68
|
||||||
#define MPU_ADDRESS 0x69
|
#define MPU_ADDRESS 0x69
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6500
|
#define USE_GYRO_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MPU9250_MAG // Enables bypass configuration on the MPU9250 I2C bus
|
#define USE_MPU9250_MAG // Enables bypass configuration on the MPU9250 I2C bus
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
#define MAG_AK8963_ALIGN CW270_DEG
|
#define MAG_AK8963_ALIGN CW270_DEG
|
||||||
|
|
|
@ -69,7 +69,7 @@
|
||||||
#define M25P16_CS_PIN PC15
|
#define M25P16_CS_PIN PC15
|
||||||
#define M25P16_SPI_INSTANCE SPI2
|
#define M25P16_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6500
|
#define USE_GYRO_MPU6500
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
@ -77,14 +77,14 @@
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
#define USE_BARO_SPI_BMP280
|
#define USE_BARO_SPI_BMP280
|
||||||
|
|
||||||
|
|
|
@ -39,11 +39,11 @@
|
||||||
#define MPU6500_CS_PIN PA5
|
#define MPU6500_CS_PIN PA5
|
||||||
|
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW90_DEG
|
#define GYRO_MPU6500_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW90_DEG
|
#define ACC_MPU6500_ALIGN CW90_DEG
|
||||||
|
|
||||||
|
@ -70,7 +70,7 @@
|
||||||
#define I2C2_SCL PA9
|
#define I2C2_SCL PA9
|
||||||
|
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
|
@ -102,7 +102,7 @@
|
||||||
#undef BEEPER
|
#undef BEEPER
|
||||||
|
|
||||||
|
|
||||||
#define BLACKBOX
|
#define USE_BLACKBOX
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
#define BRUSHED_MOTORS
|
#define BRUSHED_MOTORS
|
||||||
|
|
|
@ -37,18 +37,18 @@
|
||||||
#define MPU6500_SPI_INSTANCE SPI2
|
#define MPU6500_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
// Using MPU6050 for the moment.
|
// Using MPU6050 for the moment.
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
//#define BARO
|
//#define USE_BARO
|
||||||
//#define USE_BARO_MS5611
|
//#define USE_BARO_MS5611
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
|
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
|
||||||
|
|
||||||
|
|
|
@ -38,19 +38,19 @@
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW90_DEG
|
#define ACC_MPU6000_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW90_DEG
|
#define GYRO_MPU6000_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define MAG_HMC5883_ALIGN CW90_DEG
|
#define MAG_HMC5883_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
|
|
|
@ -53,7 +53,7 @@
|
||||||
#define ICM20689_CS_PIN PA8
|
#define ICM20689_CS_PIN PA8
|
||||||
#define ICM20689_SPI_INSTANCE SPI1
|
#define ICM20689_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW180_DEG
|
#define GYRO_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -66,7 +66,7 @@
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW180_DEG
|
#define ACC_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -87,7 +87,7 @@
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
/*-------------OSD-----------------*/
|
/*-------------OSD-----------------*/
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN PB3
|
#define MAX7456_SPI_CS_PIN PB3
|
||||||
|
@ -119,7 +119,7 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 5
|
#define SERIAL_PORT_COUNT 5
|
||||||
//SPECKTRUM BIND
|
//SPECKTRUM BIND
|
||||||
#define CMS
|
#define USE_CMS
|
||||||
#define USE_MSP_DISPLAYPORT
|
#define USE_MSP_DISPLAYPORT
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
|
|
|
@ -43,11 +43,11 @@
|
||||||
#define MPU_INT_EXTI PA15
|
#define MPU_INT_EXTI PA15
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
|
|
@ -47,7 +47,7 @@
|
||||||
#define ICM20689_CS_PIN PA4
|
#define ICM20689_CS_PIN PA4
|
||||||
#define ICM20689_SPI_INSTANCE SPI1
|
#define ICM20689_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW180_DEG
|
#define GYRO_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -60,7 +60,7 @@
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW180_DEG
|
#define ACC_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -100,7 +100,7 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
|
|
||||||
#define CMS
|
#define USE_CMS
|
||||||
#define USE_MSP_DISPLAYPORT
|
#define USE_MSP_DISPLAYPORT
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
|
|
|
@ -40,11 +40,11 @@
|
||||||
#define MPU6500_CS_PIN PA4
|
#define MPU6500_CS_PIN PA4
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW90_DEG
|
#define GYRO_MPU6500_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW90_DEG
|
#define ACC_MPU6500_ALIGN CW90_DEG
|
||||||
|
|
||||||
|
@ -80,7 +80,7 @@
|
||||||
#define SPI2_MISO_PIN PC2
|
#define SPI2_MISO_PIN PC2
|
||||||
#define SPI2_MOSI_PIN PC3
|
#define SPI2_MOSI_PIN PC3
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI2
|
#define MAX7456_SPI_INSTANCE SPI2
|
||||||
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
|
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
|
||||||
|
|
|
@ -36,19 +36,19 @@
|
||||||
#ifdef MYMPU6000
|
#ifdef MYMPU6000
|
||||||
#define MPU6000_SPI_INSTANCE SPI2
|
#define MPU6000_SPI_INSTANCE SPI2
|
||||||
#define MPU6000_CS_PIN PB12
|
#define MPU6000_CS_PIN PB12
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
#else
|
#else
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define GYRO_MPU6050_ALIGN CW270_DEG
|
#define GYRO_MPU6050_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
#define ACC_MPU6050_ALIGN CW270_DEG
|
#define ACC_MPU6050_ALIGN CW270_DEG
|
||||||
#endif
|
#endif
|
||||||
|
@ -80,7 +80,7 @@
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_PIN PB9 // (HARDARE=0)
|
#define ESCSERIAL_TIMER_TX_PIN PB9 // (HARDARE=0)
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
|
|
||||||
// include the max7456 driver
|
// include the max7456 driver
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
|
|
|
@ -28,10 +28,10 @@
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
|
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
|
@ -41,13 +41,13 @@
|
||||||
#define MPU_INT_EXTI PC4
|
#define MPU_INT_EXTI PC4
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
#define USE_BARO_SPI_BMP280
|
#define USE_BARO_SPI_BMP280
|
||||||
#define BMP280_SPI_INSTANCE SPI3
|
#define BMP280_SPI_INSTANCE SPI3
|
||||||
#define BMP280_CS_PIN PB3
|
#define BMP280_CS_PIN PB3
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN PA15
|
#define MAX7456_SPI_CS_PIN PA15
|
||||||
|
|
|
@ -47,7 +47,7 @@
|
||||||
#define MPU6500_CS_PIN PA4
|
#define MPU6500_CS_PIN PA4
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW180_DEG
|
#define GYRO_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -58,7 +58,7 @@
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW90_DEG
|
#define GYRO_MPU6500_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW180_DEG
|
#define ACC_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -79,7 +79,7 @@
|
||||||
#define SPI2_MOSI_PIN PB15
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
#ifdef FURYF3OSD
|
#ifdef FURYF3OSD
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
// include the max7456 driver
|
// include the max7456 driver
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI1
|
#define MAX7456_SPI_INSTANCE SPI1
|
||||||
|
@ -120,7 +120,7 @@
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -143,7 +143,7 @@
|
||||||
#define SOFTSERIAL1_RX_PIN PB0
|
#define SOFTSERIAL1_RX_PIN PB0
|
||||||
#define SOFTSERIAL1_TX_PIN PB1
|
#define SOFTSERIAL1_TX_PIN PB1
|
||||||
|
|
||||||
#define SONAR
|
#define USE_SONAR
|
||||||
#define SONAR_ECHO_PIN PB1
|
#define SONAR_ECHO_PIN PB1
|
||||||
#define SONAR_TRIGGER_PIN PB0
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
|
|
|
@ -47,7 +47,7 @@
|
||||||
#define MPU6500_CS_PIN PA4
|
#define MPU6500_CS_PIN PA4
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW180_DEG
|
#define GYRO_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -60,7 +60,7 @@
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW180_DEG
|
#define ACC_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
@ -72,7 +72,7 @@
|
||||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||||
|
|
||||||
#ifdef FURYF4OSD
|
#ifdef FURYF4OSD
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI2
|
#define MAX7456_SPI_INSTANCE SPI2
|
||||||
#define MAX7456_SPI_CS_PIN PB12
|
#define MAX7456_SPI_CS_PIN PB12
|
||||||
|
@ -85,7 +85,7 @@
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
#define MS5611_I2C_INSTANCE I2CDEV_1
|
#define MS5611_I2C_INSTANCE I2CDEV_1
|
||||||
|
|
||||||
|
|
|
@ -34,15 +34,15 @@
|
||||||
#define ICM20689_CS_PIN PA4
|
#define ICM20689_CS_PIN PA4
|
||||||
#define ICM20689_SPI_INSTANCE SPI1
|
#define ICM20689_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW180_DEG
|
#define GYRO_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW180_DEG
|
#define ACC_ICM20689_ALIGN CW180_DEG
|
||||||
|
|
||||||
//#define BARO
|
//#define USE_BARO
|
||||||
//#define USE_BARO_MS5611
|
//#define USE_BARO_MS5611
|
||||||
//#define MS5611_I2C_INSTANCE I2CDEV_1
|
//#define MS5611_I2C_INSTANCE I2CDEV_1
|
||||||
|
|
||||||
|
|
|
@ -32,11 +32,11 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW0_DEG
|
#define GYRO_MPU6000_ALIGN CW0_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW0_DEG
|
#define ACC_MPU6000_ALIGN CW0_DEG
|
||||||
|
|
||||||
|
@ -79,7 +79,7 @@
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI1
|
#define MAX7456_SPI_INSTANCE SPI1
|
||||||
#define MAX7456_SPI_CS_PIN PA3
|
#define MAX7456_SPI_CS_PIN PA3
|
||||||
|
|
|
@ -28,15 +28,15 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define GYRO_MPU6050_ALIGN CW270_DEG
|
#define GYRO_MPU6050_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
#define ACC_MPU6050_ALIGN CW270_DEG
|
#define ACC_MPU6050_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP085
|
#define USE_BARO_BMP085
|
||||||
|
|
||||||
#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
|
|
|
@ -35,21 +35,21 @@
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6500
|
#define USE_GYRO_MPU6500
|
||||||
//#define USE_GYRO_SPI_MPU6500
|
//#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
//#define USE_ACC_SPI_MPU6500
|
//#define USE_ACC_SPI_MPU6500
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
|
|
||||||
#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define SONAR
|
#define USE_SONAR
|
||||||
#define SONAR_TRIGGER_PIN PB0
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
#define SONAR_ECHO_PIN PB1
|
#define SONAR_ECHO_PIN PB1
|
||||||
|
|
||||||
|
|
|
@ -44,11 +44,11 @@
|
||||||
#define ICM20689_CS_PIN PC4
|
#define ICM20689_CS_PIN PC4
|
||||||
#define ICM20689_SPI_INSTANCE SPI1
|
#define ICM20689_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
#define ACC_ICM20689_ALIGN CW270_DEG
|
#define ACC_ICM20689_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_ICM20689
|
#define USE_GYRO_SPI_ICM20689
|
||||||
#define GYRO_ICM20689_ALIGN CW270_DEG
|
#define GYRO_ICM20689_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
@ -65,12 +65,12 @@
|
||||||
#define USE_MAG_HMC5883 //External, connect to I2C1
|
#define USE_MAG_HMC5883 //External, connect to I2C1
|
||||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611 //External, connect to I2C1
|
#define USE_BARO_MS5611 //External, connect to I2C1
|
||||||
#define USE_BARO_BMP280 //onboard
|
#define USE_BARO_BMP280 //onboard
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI3
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
#define MAX7456_SPI_CS_PIN PB14
|
#define MAX7456_SPI_CS_PIN PB14
|
||||||
|
|
|
@ -25,8 +25,8 @@
|
||||||
#define BEEPER PD15
|
#define BEEPER PD15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_DUAL_GYRO
|
#define USE_DUAL_GYRO
|
||||||
|
|
||||||
// ICM-20689
|
// ICM-20689
|
||||||
|
@ -118,7 +118,7 @@
|
||||||
#define SPI4_MOSI_PIN PE6
|
#define SPI4_MOSI_PIN PE6
|
||||||
|
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#define MAX7456_SPI_INSTANCE SPI2
|
#define MAX7456_SPI_INSTANCE SPI2
|
||||||
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
|
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
|
||||||
|
@ -150,11 +150,11 @@
|
||||||
#define I2C1_SCL PB6
|
#define I2C1_SCL PB6
|
||||||
#define I2C1_SDA PB7
|
#define I2C1_SDA PB7
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
#define BARO_I2C_INSTANCE I2C_DEVICE
|
#define BARO_I2C_INSTANCE I2C_DEVICE
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define MAG_I2C_INSTANCE I2C_DEVICE
|
#define MAG_I2C_INSTANCE I2C_DEVICE
|
||||||
|
|
||||||
|
|
|
@ -41,20 +41,20 @@
|
||||||
#ifdef KISSCC
|
#ifdef KISSCC
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define GYRO_MPU6050_ALIGN CW90_DEG
|
#define GYRO_MPU6050_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
#define ACC_MPU6050_ALIGN CW90_DEG
|
#define ACC_MPU6050_ALIGN CW90_DEG
|
||||||
#undef LED_STRIP
|
#undef LED_STRIP
|
||||||
#else
|
#else
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define GYRO_MPU6050_ALIGN CW180_DEG
|
#define GYRO_MPU6050_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_MPU6050
|
#define USE_ACC_MPU6050
|
||||||
#define ACC_MPU6050_ALIGN CW180_DEG
|
#define ACC_MPU6050_ALIGN CW180_DEG
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -51,7 +51,7 @@
|
||||||
#define MPU6000_CS_PIN PA4
|
#define MPU6000_CS_PIN PA4
|
||||||
#define MPU6000_SPI_INSTANCE SPI1
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
|
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||||
|
@ -62,7 +62,7 @@
|
||||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
#if defined(KIWIF4) || defined(KIWIF4V2)
|
#if defined(KIWIF4) || defined(KIWIF4V2)
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#define USE_MAX7456
|
#define USE_MAX7456
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -189,5 +189,5 @@
|
||||||
|
|
||||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) )
|
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) )
|
||||||
|
|
||||||
#define CMS
|
#define USE_CMS
|
||||||
#define USE_MSP_DISPLAYPORT
|
#define USE_MSP_DISPLAYPORT
|
||||||
|
|
|
@ -43,20 +43,20 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
#define MPU_INT_EXTI PA4
|
#define MPU_INT_EXTI PA4
|
||||||
|
|
||||||
#define GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW90_DEG
|
#define GYRO_MPU6000_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define MAG
|
#define USE_MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||||
#define MAG_I2C_INSTANCE I2CDEV_1
|
#define MAG_I2C_INSTANCE I2CDEV_1
|
||||||
|
|
||||||
#define BARO
|
#define USE_BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
|
@ -72,7 +72,7 @@
|
||||||
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
||||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||||
|
|
||||||
#define OSD
|
#define USE_OSD
|
||||||
#ifdef USE_MSP_DISPLAYPORT
|
#ifdef USE_MSP_DISPLAYPORT
|
||||||
#undef USE_MSP_DISPLAYPORT
|
#undef USE_MSP_DISPLAYPORT
|
||||||
#endif
|
#endif
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue