1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 09:45:33 +03:00

added USE_SIMULATOR

reverted unrelated changes
This commit is contained in:
Roman Lut 2022-07-30 04:58:46 +03:00
parent 907bbe88b5
commit d9637e5d7f
26 changed files with 120 additions and 130 deletions

View file

@ -178,6 +178,7 @@ int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint16_t c)
displayUpdateMaxChar(instance); displayUpdateMaxChar(instance);
} }
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
//some FCs do not power max7456 from USB power //some FCs do not power max7456 from USB power
//driver can not read font metadata //driver can not read font metadata
@ -186,6 +187,7 @@ int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint16_t c)
//return dummy metadata to let all OSD elements to work in simulator mode //return dummy metadata to let all OSD elements to work in simulator mode
instance->maxChar = 512; instance->maxChar = 512;
} }
#endif
if (c > instance->maxChar) { if (c > instance->maxChar) {
return -1; return -1;

View file

@ -46,9 +46,13 @@ void systemBeep(bool onoff)
UNUSED(onoff); UNUSED(onoff);
#else #else
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) {
if (simulatorData.flags & SIMU_MUTE_BEEPER) { if (simulatorData.flags & SIMU_MUTE_BEEPER) {
onoff = false; onoff = false;
} }
}
#endif
if (beeperConfig()->pwmMode) { if (beeperConfig()->pwmMode) {
pwmWriteBeeper(onoff); pwmWriteBeeper(onoff);

View file

@ -1734,19 +1734,6 @@ static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const s
} }
} }
static void cliOutput(char *cmdline)
{
// print out servo output
cliPrintHashLine("servo");
const char *format = "servo %u %d";
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
cliPrintLinef(format,
i,
getServoValue(i)
);
}
}
static void cliServo(char *cmdline) static void cliServo(char *cmdline)
{ {
enum { SERVO_ARGUMENT_COUNT = 5 }; enum { SERVO_ARGUMENT_COUNT = 5 };

View file

@ -942,13 +942,26 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
} }
//Servos should be filtered or written only when mixer is using servos or special feaures are enabled //Servos should be filtered or written only when mixer is using servos or special feaures are enabled
if (isServoOutputEnabled() && ! ARMING_FLAG(SIMULATOR_MODE)) {
#ifdef USE_SMULATOR
if (!ARMING_FLAG(SIMULATOR_MODE)) {
if (isServoOutputEnabled()) {
writeServos(); writeServos();
} }
if (motorControlEnable && ! ARMING_FLAG(SIMULATOR_MODE)) { if (motorControlEnable) {
writeMotors(); writeMotors();
} }
}
#else
if (isServoOutputEnabled()) {
writeServos();
}
if (motorControlEnable) {
writeMotors();
}
#endif
// Check if landed, FW and MR // Check if landed, FW and MR
if (STATE(ALTITUDE_CONTROL)) { if (STATE(ALTITUDE_CONTROL)) {

View file

@ -3474,10 +3474,6 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
gpsSol.groundSpeed = (int16_t)sbufReadU16(src); gpsSol.groundSpeed = (int16_t)sbufReadU16(src);
gpsSol.groundCourse = (int16_t)sbufReadU16(src); gpsSol.groundCourse = (int16_t)sbufReadU16(src);
//gpsSol.velNED[X] = gpsSol.groundSpeed * cos_approx(DECIDEGREES_TO_RADIANS(gpsSol.groundCourse));
//gpsSol.velNED[Y] = gpsSol.groundSpeed * sin_approx(DECIDEGREES_TO_RADIANS(gpsSol.groundCourse));
//gpsSol.velNED[Z] = 0;
gpsSol.velNED[X] = (int16_t)sbufReadU16(src); gpsSol.velNED[X] = (int16_t)sbufReadU16(src);
gpsSol.velNED[Y] = (int16_t)sbufReadU16(src); gpsSol.velNED[Y] = (int16_t)sbufReadU16(src);
gpsSol.velNED[Z] = (int16_t)sbufReadU16(src); gpsSol.velNED[Z] = (int16_t)sbufReadU16(src);
@ -3485,25 +3481,6 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
gpsSol.eph = 100; gpsSol.eph = 100;
gpsSol.epv = 100; gpsSol.epv = 100;
/*
//------------------------
gpsSol.flags.validVelNE = 0;
gpsSol.flags.validVelD = 0;
gpsSol.flags.validEPE = 0;
debug[0] = gpsSol.velNED[X];
debug[1] = gpsSol.velNED[Y];
debug[2] = gpsSol.velNED[Z];
debug[3] = posEstimator.gps.vel.x;
debug[4] = posEstimator.gps.vel.y;
debug[5] = posEstimator.gps.vel.z;
debug[6] = gpsSol.groundSpeed * cos_approx(DECIDEGREES_TO_RADIANS(gpsSol.groundCourse));
debug[7] = gpsSol.groundSpeed * sin_approx(DECIDEGREES_TO_RADIANS(gpsSol.groundCourse));
//------------------------
*/
ENABLE_STATE(GPS_FIX); ENABLE_STATE(GPS_FIX);
// Feed data to navigation // Feed data to navigation
@ -3526,16 +3503,6 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
else else
{ {
sbufAdvance(src, 2*3); sbufAdvance(src, 2*3);
/*
debug[0] = (int16_t)sbufReadU16(src);
debug[1] = (int16_t)sbufReadU16(src);
debug[2] = (int16_t)sbufReadU16(src);
debug[3] = attitude.values.roll;
debug[4] = attitude.values.pitch;
debug[5] = attitude.values.yaw;
*/
} }
acc.accADCf[X] = ((int16_t)sbufReadU16(src)) / 1000.0f;// acceleration in 1G units acc.accADCf[X] = ((int16_t)sbufReadU16(src)) / 1000.0f;// acceleration in 1G units
@ -3551,7 +3518,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
if (sensors(SENSOR_BARO)) if (sensors(SENSOR_BARO))
{ {
baro.baroPressure = sbufReadU32(src); baro.baroPressure = (int32_t)sbufReadU32(src);
baro.baroTemperature = 2500; baro.baroTemperature = 2500;
} }
else { else {
@ -3573,10 +3540,10 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
} }
} }
sbufWriteU16(dst, (uint16_t)input[INPUT_STABILIZED_ROLL]); sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_ROLL);
sbufWriteU16(dst, (uint16_t)input[INPUT_STABILIZED_PITCH]); sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_PITCH);
sbufWriteU16(dst, (uint16_t)input[INPUT_STABILIZED_YAW]); sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_YAW);
sbufWriteU16(dst, (uint16_t)(ARMING_FLAG(ARMED) ? input[INPUT_STABILIZED_THROTTLE] : -500)); sbufWriteU16(dst, (uint16_t)(ARMING_FLAG(ARMED) ? simulatorData.INPUT_STABILIZED_THROTTLE : -500));
/* /*
debug[0] = mag.magADC[X]; debug[0] = mag.magADC[X];

View file

@ -306,9 +306,13 @@ void taskUpdateAux(timeUs_t currentTimeUs)
{ {
updatePIDCoefficients(); updatePIDCoefficients();
dynamicLpfGyroTask(); dynamicLpfGyroTask();
#ifdef USE_SIMULATOR
if (!ARMING_FLAG(SIMULATOR_MODE)) { if (!ARMING_FLAG(SIMULATOR_MODE)) {
updateFixedWingLevelTrim(currentTimeUs); updateFixedWingLevelTrim(currentTimeUs);
} }
#else
updateFixedWingLevelTrim(currentTimeUs);
#endif
} }
void fcTasksInit(void) void fcTasksInit(void)

View file

@ -177,4 +177,13 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)
return STATE(AIRMODE_ACTIVE) ? FLM_ACRO_AIR : FLM_ACRO; return STATE(AIRMODE_ACTIVE) ? FLM_ACRO_AIR : FLM_ACRO;
} }
simulatorData_t simulatorData = { flags: 0, debugIndex: 0 }; #ifdef USE_SIMULATOR
simulatorData_t simulatorData = {
flags: 0,
debugIndex: 0,
INPUT_STABILIZED_ROLL: 0,
INPUT_STABILIZED_PITCH: 0,
INPUT_STABILIZED_YAW: 0,
INPUT_STABILIZED_THROTTLE: 0
};
#endif

View file

@ -165,7 +165,7 @@ typedef enum {
flightModeForTelemetry_e getFlightModeForTelemetry(void); flightModeForTelemetry_e getFlightModeForTelemetry(void);
#ifdef USE_SIMULATOR
typedef enum { typedef enum {
SIMU_ENABLE = (1 << 0), SIMU_ENABLE = (1 << 0),
SIMU_SIMULATE_BATTERY = (1 << 1), SIMU_SIMULATE_BATTERY = (1 << 1),
@ -177,9 +177,14 @@ typedef enum {
typedef struct { typedef struct {
simulatorFlags_t flags; simulatorFlags_t flags;
uint8_t debugIndex; uint8_t debugIndex;
int16_t INPUT_STABILIZED_ROLL;
int16_t INPUT_STABILIZED_PITCH;
int16_t INPUT_STABILIZED_YAW;
int16_t INPUT_STABILIZED_THROTTLE;
} simulatorData_t; } simulatorData_t;
extern simulatorData_t simulatorData; extern simulatorData_t simulatorData;
#endif
uint32_t enableFlightMode(flightModeFlags_e mask); uint32_t enableFlightMode(flightModeFlags_e mask);
uint32_t disableFlightMode(flightModeFlags_e mask); uint32_t disableFlightMode(flightModeFlags_e mask);

View file

@ -2476,7 +2476,7 @@ groups:
description: "Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]" description: "Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]"
default_value: 50 default_value: 50
field: general.land_minalt_vspd field: general.land_minalt_vspd
min: 0 min: 50
max: 500 max: 500
- name: nav_land_maxalt_vspd - name: nav_land_maxalt_vspd
description: "Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]" description: "Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]"

View file

@ -327,9 +327,11 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
// Normalize to unit vector // Normalize to unit vector
vectorNormalize(&vMag, &vMag); vectorNormalize(&vMag, &vMag);
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
imuSetMagneticDeclination(0); imuSetMagneticDeclination(0);
} }
#endif
// Reference mag field vector heading is Magnetic North in EF. We compute that by rotating True North vector by declination and assuming Z-component is zero // Reference mag field vector heading is Magnetic North in EF. We compute that by rotating True North vector by declination and assuming Z-component is zero
// magnetometer error is cross product between estimated magnetic north and measured magnetic north (calculated in EF) // magnetometer error is cross product between estimated magnetic north and measured magnetic north (calculated in EF)
@ -459,11 +461,13 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
STATIC_UNIT_TESTED void imuUpdateEulerAngles(void) STATIC_UNIT_TESTED void imuUpdateEulerAngles(void)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE) && ((simulatorData.flags & SIMU_USE_SENSORS) == 0)) { if (ARMING_FLAG(SIMULATOR_MODE) && ((simulatorData.flags & SIMU_USE_SENSORS) == 0)) {
imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw); imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw);
imuComputeRotationMatrix(); imuComputeRotationMatrix();
} }
else else
#endif
{ {
/* Compute pitch/roll angles */ /* Compute pitch/roll angles */
attitude.values.roll = RADIANS_TO_DECIDEGREES(atan2_approx(rMat[2][1], rMat[2][2])); attitude.values.roll = RADIANS_TO_DECIDEGREES(atan2_approx(rMat[2][1], rMat[2][2]));

View file

@ -101,7 +101,6 @@ void pgResetFn_servoParams(servoParam_t *instance)
} }
} }
int16_t input[INPUT_SOURCE_COUNT]; // Range [-500:+500]
int16_t servo[MAX_SUPPORTED_SERVOS]; int16_t servo[MAX_SUPPORTED_SERVOS];
static uint8_t servoRuleCount = 0; static uint8_t servoRuleCount = 0;
@ -246,6 +245,8 @@ void writeServos(void)
void servoMixer(float dT) void servoMixer(float dT)
{ {
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];
@ -319,6 +320,13 @@ void servoMixer(float dT)
input[INPUT_RC_CH16] = GET_RX_CHANNEL_INPUT(AUX12); input[INPUT_RC_CH16] = GET_RX_CHANNEL_INPUT(AUX12);
#undef GET_RX_CHANNEL_INPUT #undef GET_RX_CHANNEL_INPUT
#ifdef USE_SIMULATOR
simulatorData.INPUT_STABILIZED_ROLL = input[INPUT_STABILIZED_ROLL];
simulatorData.INPUT_STABILIZED_PITCH = input[INPUT_STABILIZED_PITCH];
simulatorData.INPUT_STABILIZED_YAW = input[INPUT_STABILIZED_YAW];
simulatorData.INPUT_STABILIZED_THROTTLE = input[INPUT_STABILIZED_THROTTLE];
#endif
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
servo[i] = 0; servo[i] = 0;
} }
@ -588,12 +596,3 @@ bool isMixerUsingServos(void)
{ {
return mixerUsesServos; return mixerUsesServos;
} }
int16_t getServoValue(uint32_t n)
{
if (n >= MAX_SUPPORTED_SERVOS) {
return;
}
return servo[n];
}

View file

@ -150,7 +150,6 @@ typedef struct servoMetadata_s {
} servoMetadata_t; } servoMetadata_t;
extern int16_t servo[MAX_SUPPORTED_SERVOS]; extern int16_t servo[MAX_SUPPORTED_SERVOS];
extern int16_t input[INPUT_SOURCE_COUNT]; // Range [-500:+500]
bool isServoOutputEnabled(void); bool isServoOutputEnabled(void);
void setServoOutputEnabled(bool flag); void setServoOutputEnabled(bool flag);
@ -161,4 +160,3 @@ void servoMixer(float dT);
void servoComputeScalingFactors(uint8_t servoIndex); void servoComputeScalingFactors(uint8_t servoIndex);
void servosInit(void); void servosInit(void);
int getServoCount(void); int getServoCount(void);
int16_t getServoValue(uint32_t n);

View file

@ -344,12 +344,14 @@ bool gpsUpdate(void)
return false; return false;
} }
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
gpsUpdateTime(); gpsUpdateTime();
gpsSetState(GPS_RUNNING); gpsSetState(GPS_RUNNING);
sensorsSet(SENSOR_GPS); sensorsSet(SENSOR_GPS);
return gpsSol.flags.hasNewData; return gpsSol.flags.hasNewData;
} }
#endif
#ifdef USE_FAKE_GPS #ifdef USE_FAKE_GPS
return gpsFakeGPSUpdate(); return gpsFakeGPSUpdate();
#else #else

View file

@ -846,8 +846,10 @@ 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;
} }
@ -4410,12 +4412,6 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
osdFormatDistanceSymbol(buf, posControl.wpDistance, 0); osdFormatDistanceSymbol(buf, posControl.wpDistance, 0);
tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf); tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf);
messages[messageCount++] = messageBuf; messages[messageCount++] = messageBuf;
} else if (NAV_Status.state == MW_NAV_STATE_RTH_ENROUTE) {
// Countdown display for RTH minutes
char buf[6];
osdFormatDistanceSymbol(buf, GPS_distanceToHome * 60 * 60 * 3.6/ gpsSol.groundSpeed , 0);
tfp_sprintf(messageBuf, "EN ROUTE TO HOME (%s)", buf);
messages[messageCount++] = messageBuf;
} else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) { } else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) {
if (navConfig()->general.flags.waypoint_enforce_altitude && !posControl.wpAltitudeReached) { if (navConfig()->general.flags.waypoint_enforce_altitude && !posControl.wpAltitudeReached) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ADJUSTING_WP_ALT); messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ADJUSTING_WP_ALT);

View file

@ -257,7 +257,6 @@
#define MSP_RC_DEADBAND 125 //out message deadbands for yaw alt pitch roll #define MSP_RC_DEADBAND 125 //out message deadbands for yaw alt pitch roll
#define MSP_SENSOR_ALIGNMENT 126 //out message orientation of acc,gyro,mag #define MSP_SENSOR_ALIGNMENT 126 //out message orientation of acc,gyro,mag
#define MSP_LED_STRIP_MODECOLOR 127 //out message Get LED strip mode_color settings #define MSP_LED_STRIP_MODECOLOR 127 //out message Get LED strip mode_color settings
#define MSP_TELEMETRY 128 //out message Get controller telemetry
#define MSP_SET_RAW_RC 200 //in message 8 rc chan #define MSP_SET_RAW_RC 200 //in message 8 rc chan
#define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed #define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed

View file

@ -146,8 +146,7 @@ static void updateAltitudeVelocityAndPitchController_FW(timeDelta_t deltaMicros)
// speedWeight = 1.0 : pitch will only control airspeed and won't control altitude // speedWeight = 1.0 : pitch will only control airspeed and won't control altitude
// speedWeight = 0.5 : pitch will be used to control both airspeed and altitude // speedWeight = 0.5 : pitch will be used to control both airspeed and altitude
// speedWeight = 0.0 : pitch will only control altitude // speedWeight = 0.0 : pitch will only control altitude
const float speedWeight = 0.7f; // no speed sensing for now const float speedWeight = 0.0f; // no speed sensing for now
// const float speedWeight = 1.0f - constrainf(fabs(demSPE - estSPE) / GRAVITY_MSS, 0.0f, 1.0f); // no speed sensing for now
const float demSEB = demSPE * (1.0f - speedWeight) - demSKE * speedWeight; const float demSEB = demSPE * (1.0f - speedWeight) - demSKE * speedWeight;
const float estSEB = estSPE * (1.0f - speedWeight) - estSKE * speedWeight; const float estSEB = estSPE * (1.0f - speedWeight) - estSKE * speedWeight;
@ -537,7 +536,6 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
if (navStateFlags & NAV_CTL_LAND) { if (navStateFlags & NAV_CTL_LAND) {
// During LAND we do not allow to raise THROTTLE when nose is up to reduce speed // During LAND we do not allow to raise THROTTLE when nose is up to reduce speed
throttleCorrection = constrain(throttleCorrection, minThrottleCorrection, 0); throttleCorrection = constrain(throttleCorrection, minThrottleCorrection, 0);
throttleCorrection = minThrottleCorrection;
} else { } else {
#endif #endif
throttleCorrection = constrain(throttleCorrection, minThrottleCorrection, maxThrottleCorrection); throttleCorrection = constrain(throttleCorrection, minThrottleCorrection, maxThrottleCorrection);

View file

@ -448,9 +448,11 @@ static void updateIMUTopic(timeUs_t currentTimeUs)
/* If calibration is incomplete - report zero acceleration */ /* If calibration is incomplete - report zero acceleration */
if (gravityCalibrationComplete()) { if (gravityCalibrationComplete()) {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
posEstimator.imu.calibratedGravityCMSS = GRAVITY_CMSS; posEstimator.imu.calibratedGravityCMSS = GRAVITY_CMSS;
} }
#endif
posEstimator.imu.accelNEU.z -= posEstimator.imu.calibratedGravityCMSS; posEstimator.imu.accelNEU.z -= posEstimator.imu.calibratedGravityCMSS;
} }
else { else {
@ -537,11 +539,6 @@ static void estimationPredict(estimationContext_t * ctx)
posEstimator.est.pos.z += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f * accWeight; posEstimator.est.pos.z += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f * accWeight;
posEstimator.est.vel.z += posEstimator.imu.accelNEU.z * ctx->dt * sq(accWeight); posEstimator.est.vel.z += posEstimator.imu.accelNEU.z * ctx->dt * sq(accWeight);
} }
/*
if (ARMING_FLAG(SIMULATOR_MODE)) {
posEstimator.est.pos.z = baro.BaroAlt;
}
*/
/* Prediction step: XY-axis */ /* Prediction step: XY-axis */
if ((ctx->newFlags & EST_XY_VALID)) { if ((ctx->newFlags & EST_XY_VALID)) {
@ -561,15 +558,6 @@ static void estimationPredict(estimationContext_t * ctx)
static bool estimationCalculateCorrection_Z(estimationContext_t * ctx) static bool estimationCalculateCorrection_Z(estimationContext_t * ctx)
{ {
DEBUG_SET(DEBUG_ALTITUDE, 0, posEstimator.est.pos.z); // Position estimate
DEBUG_SET(DEBUG_ALTITUDE, 2, imuMeasuredAccelBF.z); // Baro altitude
DEBUG_SET(DEBUG_ALTITUDE, 4, posEstimator.gps.pos.z); // GPS altitude
DEBUG_SET(DEBUG_ALTITUDE, 6, accGetVibrationLevel()); // Vibration level
DEBUG_SET(DEBUG_ALTITUDE, 1, posEstimator.est.vel.z); // Vertical speed estimate
DEBUG_SET(DEBUG_ALTITUDE, 3, posEstimator.imu.accelNEU.z); // Vertical acceleration on earth frame
DEBUG_SET(DEBUG_ALTITUDE, 5, posEstimator.gps.vel.z); // GPS vertical speed
DEBUG_SET(DEBUG_ALTITUDE, 7, accGetClipCount()); // Clip count
if (ctx->newFlags & EST_BARO_VALID) { if (ctx->newFlags & EST_BARO_VALID) {
timeUs_t currentTimeUs = micros(); timeUs_t currentTimeUs = micros();
@ -640,6 +628,15 @@ static bool estimationCalculateCorrection_Z(estimationContext_t * ctx)
return true; return true;
} }
DEBUG_SET(DEBUG_ALTITUDE, 0, posEstimator.est.pos.z); // Position estimate
DEBUG_SET(DEBUG_ALTITUDE, 2, imuMeasuredAccelBF.z); // Baro altitude
DEBUG_SET(DEBUG_ALTITUDE, 4, posEstimator.gps.pos.z); // GPS altitude
DEBUG_SET(DEBUG_ALTITUDE, 6, accGetVibrationLevel()); // Vibration level
DEBUG_SET(DEBUG_ALTITUDE, 1, posEstimator.est.vel.z); // Vertical speed estimate
DEBUG_SET(DEBUG_ALTITUDE, 3, posEstimator.imu.accelNEU.z); // Vertical acceleration on earth frame
DEBUG_SET(DEBUG_ALTITUDE, 5, posEstimator.gps.vel.z); // GPS vertical speed
DEBUG_SET(DEBUG_ALTITUDE, 7, accGetClipCount()); // Clip count
return false; return false;
} }
@ -861,7 +858,6 @@ void initializePositionEstimator(void)
pt1FilterInit(&posEstimator.surface.avgFilter, INAV_SURFACE_AVERAGE_HZ, 0.0f); pt1FilterInit(&posEstimator.surface.avgFilter, INAV_SURFACE_AVERAGE_HZ, 0.0f);
} }
static bool isInitialized = false;
/** /**
* Update estimator * Update estimator
@ -869,8 +865,7 @@ static bool isInitialized = false;
*/ */
void updatePositionEstimator(void) void updatePositionEstimator(void)
{ {
// todo: why this const is inside function? static bool isInitialized = false;
// static bool isInitialized = false;
if (!isInitialized) { if (!isInitialized) {
initializePositionEstimator(); initializePositionEstimator();

View file

@ -503,18 +503,19 @@ float accGetMeasuredMaxG(void)
void accUpdate(void) void accUpdate(void)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
//output: acc.accADCf //output: acc.accADCf
//unused: acc.dev.ADCRaw[], acc.accClipCount, acc.accVibeSq[] //unused: acc.dev.ADCRaw[], acc.accClipCount, acc.accVibeSq[]
return; return;
} }
#endif
if (!acc.dev.readFn(&acc.dev)) { if (!acc.dev.readFn(&acc.dev)) {
return; return;
} }
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();

View file

@ -276,11 +276,14 @@ uint32_t baroUpdate(void)
if (baro.dev.start_ut) { if (baro.dev.start_ut) {
baro.dev.start_ut(&baro.dev); baro.dev.start_ut(&baro.dev);
} }
#ifdef USE_SIMULATOR
if (!ARMING_FLAG(SIMULATOR_MODE)) { if (!ARMING_FLAG(SIMULATOR_MODE)) {
//output: baro.baroPressure, baro.baroTemperature //output: baro.baroPressure, baro.baroTemperature
baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature);
} }
#else
baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature);
#endif
state = BAROMETER_NEEDS_SAMPLES; state = BAROMETER_NEEDS_SAMPLES;
return baro.dev.ut_delay; return baro.dev.ut_delay;
break; break;
@ -320,12 +323,16 @@ int32_t baroCalculateAltitude(void)
} }
baro.BaroAlt = 0; baro.BaroAlt = 0;
baro.BaroMslAlt = 0;
} }
else { else {
#ifdef HIL
if (hilActive) {
baro.BaroAlt = hilToFC.baroAlt;
return baro.BaroAlt;
}
#endif
// calculates height from ground via baro readings // calculates height from ground via baro readings
baro.BaroMslAlt = pressureToAltitude(baro.baroPressure); baro.BaroMslAlt = pressureToAltitude(baro.baroPressure) - baroGroundAltitude;
baro.BaroAlt = baro.BaroMslAlt - baroGroundAltitude;
} }
return baro.BaroAlt; return baro.BaroAlt;

View file

@ -41,9 +41,8 @@ typedef enum {
typedef struct baro_s { typedef struct baro_s {
baroDev_t dev; baroDev_t dev;
int32_t BaroAlt; int32_t BaroAlt;
int32_t BaroMslAlt;
int32_t baroTemperature; // Use temperature for telemetry int32_t baroTemperature; // Use temperature for telemetry
uint32_t baroPressure; // Use pressure for telemetry int32_t baroPressure; // Use pressure for telemetry
} baro_t; } baro_t;
extern baro_t baro; extern baro_t baro;

View file

@ -290,13 +290,16 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected)
vbat = 0; vbat = 0;
break; break;
} }
#ifdef USE_SIMULATOR
if (!ARMING_FLAG(SIMULATOR_MODE)) {
if (simulatorData.flags & SIMU_SIMULATE_BATTERY) { if (simulatorData.flags & SIMU_SIMULATE_BATTERY) {
vbat = 1260; vbat = 1260;
batteryFullVoltage = 1210; batteryFullVoltage = 1210;
batteryWarningVoltage = 1020; batteryWarningVoltage = 1020;
batteryCriticalVoltage = 960; batteryCriticalVoltage = 960;
} }
}
#endif
if (justConnected) { if (justConnected) {
pt1FilterReset(&vbatFilterState, vbat); pt1FilterReset(&vbatFilterState, vbat);
} else { } else {

View file

@ -356,11 +356,12 @@ bool compassIsCalibrationComplete(void)
void compassUpdate(timeUs_t currentTimeUs) void compassUpdate(timeUs_t currentTimeUs)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
magUpdatedAtLeastOnce = 1; magUpdatedAtLeastOnce = 1;
return; return;
} }
#endif
static sensorCalibrationState_t calState; static sensorCalibrationState_t calState;
static timeUs_t calStartedAt = 0; static timeUs_t calStartedAt = 0;
static int16_t magPrev[XYZ_AXIS_COUNT]; static int16_t magPrev[XYZ_AXIS_COUNT];

View file

@ -63,11 +63,11 @@ hardwareSensorStatus_e getHwAccelerometerStatus(void)
hardwareSensorStatus_e getHwCompassStatus(void) hardwareSensorStatus_e getHwCompassStatus(void)
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
return HW_SENSOR_OK; return HW_SENSOR_OK;
return;
} }
#endif
#if defined(USE_MAG) #if defined(USE_MAG)
if (detectedSensors[SENSOR_INDEX_MAG] != MAG_NONE) { if (detectedSensors[SENSOR_INDEX_MAG] != MAG_NONE) {
if (compassIsHealthy()) { if (compassIsHealthy()) {

View file

@ -437,12 +437,6 @@ static bool FAST_CODE NOINLINE gyroUpdateAndCalibrate(gyroDev_t * gyroDev, zeroC
void FAST_CODE NOINLINE gyroFilter() void FAST_CODE NOINLINE gyroFilter()
{ {
/*
if (ARMING_FLAG(SIMULATOR_MODE)) {
return;
}
*/
if (!gyro.initialized) { if (!gyro.initialized) {
return; return;
} }
@ -505,12 +499,13 @@ void FAST_CODE NOINLINE gyroFilter()
void FAST_CODE NOINLINE gyroUpdate() void FAST_CODE NOINLINE gyroUpdate()
{ {
#ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE)) { if (ARMING_FLAG(SIMULATOR_MODE)) {
//output: gyro.gyroADCf[axis] //output: gyro.gyroADCf[axis]
//unused: dev->gyroADCRaw[], dev->gyroZero[]; //unused: dev->gyroADCRaw[], dev->gyroZero[];
return; return;
} }
#endif
if (!gyro.initialized) { if (!gyro.initialized) {
return; return;
} }

View file

@ -127,19 +127,19 @@
#define UART2_TX_PIN PA2 #define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3 #define UART2_RX_PIN PA3
//#define USE_UART3 #define USE_UART3
//#define UART3_TX_PIN PB10 #define UART3_TX_PIN PB10
//#define UART3_RX_PIN PB11 #define UART3_RX_PIN PB11
#define USE_UART4 #define USE_UART4
#define UART4_TX_PIN PA0 #define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1 #define UART4_RX_PIN PA1
//#define USE_UART6 #define USE_UART6
//#define UART6_TX_PIN PC6 #define UART6_TX_PIN PC6
//#define UART6_RX_PIN PC7 #define UART6_RX_PIN PC7
#define SERIAL_PORT_COUNT 4 #define SERIAL_PORT_COUNT 6
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_PROVIDER SERIALRX_SBUS

View file

@ -193,4 +193,6 @@
#define USE_TELEMETRY_HOTT #define USE_TELEMETRY_HOTT
#define USE_HOTT_TEXTMODE #define USE_HOTT_TEXTMODE
#define USE_SIMULATOR
#endif #endif