mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 09:45:33 +03:00
reverted unrelated changes
This commit is contained in:
parent
c36154172e
commit
42a8ce15c1
9 changed files with 15 additions and 42 deletions
|
@ -3395,31 +3395,6 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
|
||||||
*ret = mspFcSafeHomeOutCommand(dst, src);
|
*ret = mspFcSafeHomeOutCommand(dst, src);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_TELEMETRY:
|
|
||||||
sbufWriteU8(dst, ARMING_FLAG(ARMED)); // arming status
|
|
||||||
sbufWriteU8(dst, 0); // modes
|
|
||||||
sbufWriteU32(dst, flightModeFlags);
|
|
||||||
|
|
||||||
sbufWriteU8(dst, 1); // messages
|
|
||||||
char buff[50] = {" "};
|
|
||||||
osdGetSystemMessage(buff, sizeof(buff), false);
|
|
||||||
const char *c = buff;
|
|
||||||
while (*c) {
|
|
||||||
sbufWriteU8(dst, *c++);
|
|
||||||
}
|
|
||||||
sbufWriteU8(dst, '\0'); // last symbol
|
|
||||||
|
|
||||||
sbufWriteU8(dst, 2); // home position
|
|
||||||
sbufWriteU16(dst, GPS_distanceToHome);
|
|
||||||
sbufWriteU16(dst, GPS_directionToHome);
|
|
||||||
sbufWriteU32(dst, baro.BaroAlt);
|
|
||||||
sbufWriteU8(dst, 3); // throttle
|
|
||||||
sbufWriteU8(dst, getThrottlePercent());
|
|
||||||
sbufWriteU8(dst, 4); // vario
|
|
||||||
sbufWriteU16(dst, getEstimatedActualVelocity(Z) + 32000);
|
|
||||||
|
|
||||||
*ret = MSP_RESULT_ACK;
|
|
||||||
break;
|
|
||||||
#ifdef USE_SIMULATOR
|
#ifdef USE_SIMULATOR
|
||||||
case MSP_SIMULATOR:
|
case MSP_SIMULATOR:
|
||||||
tmp_u8 = sbufReadU8(src); //MSP_SIMULATOR version
|
tmp_u8 = sbufReadU8(src); //MSP_SIMULATOR version
|
||||||
|
|
|
@ -246,6 +246,7 @@ void writeServos(void)
|
||||||
void servoMixer(float dT)
|
void servoMixer(float dT)
|
||||||
{
|
{
|
||||||
int16_t input[INPUT_SOURCE_COUNT]; // Range [-500:+500]
|
int16_t input[INPUT_SOURCE_COUNT]; // Range [-500:+500]
|
||||||
|
|
||||||
if (FLIGHT_MODE(MANUAL_MODE)) {
|
if (FLIGHT_MODE(MANUAL_MODE)) {
|
||||||
input[INPUT_STABILIZED_ROLL] = rcCommand[ROLL];
|
input[INPUT_STABILIZED_ROLL] = rcCommand[ROLL];
|
||||||
input[INPUT_STABILIZED_PITCH] = rcCommand[PITCH];
|
input[INPUT_STABILIZED_PITCH] = rcCommand[PITCH];
|
||||||
|
|
|
@ -846,10 +846,8 @@ static const char * osdArmingDisabledReasonMessage(void)
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
case ARMED:
|
case ARMED:
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
#ifdef USE_SIMULATOR
|
|
||||||
case SIMULATOR_MODE:
|
case SIMULATOR_MODE:
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
#endif
|
|
||||||
case WAS_EVER_ARMED:
|
case WAS_EVER_ARMED:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
|
@ -537,10 +537,8 @@ static char * osdArmingDisabledReasonMessage(void)
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
case ARMED:
|
case ARMED:
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
#ifdef USE_SIMULATOR
|
|
||||||
case SIMULATOR_MODE:
|
case SIMULATOR_MODE:
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
#endif
|
|
||||||
case WAS_EVER_ARMED:
|
case WAS_EVER_ARMED:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
|
@ -516,6 +516,7 @@ void accUpdate(void)
|
||||||
|
|
||||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||||
accADC[axis] = acc.dev.ADCRaw[axis];
|
accADC[axis] = acc.dev.ADCRaw[axis];
|
||||||
|
DEBUG_SET(DEBUG_ACC, axis, accADC[axis]);
|
||||||
}
|
}
|
||||||
|
|
||||||
performAcclerationCalibration();
|
performAcclerationCalibration();
|
||||||
|
|
|
@ -184,6 +184,8 @@
|
||||||
// Wind estimator
|
// Wind estimator
|
||||||
#define USE_WIND_ESTIMATOR
|
#define USE_WIND_ESTIMATOR
|
||||||
|
|
||||||
|
#define USE_SIMULATOR
|
||||||
|
|
||||||
//Designed to free space of F722 and F411 MCUs
|
//Designed to free space of F722 and F411 MCUs
|
||||||
#if (MCU_FLASH_SIZE > 512)
|
#if (MCU_FLASH_SIZE > 512)
|
||||||
|
|
||||||
|
@ -193,6 +195,4 @@
|
||||||
#define USE_TELEMETRY_HOTT
|
#define USE_TELEMETRY_HOTT
|
||||||
#define USE_HOTT_TEXTMODE
|
#define USE_HOTT_TEXTMODE
|
||||||
|
|
||||||
#define USE_SIMULATOR
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue