mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: improve MegaSquirt simulator fidelity
This commit is contained in:
parent
ca16e924db
commit
a018bed042
@ -41,16 +41,18 @@ void EFI_MegaSquirt::update()
|
|||||||
if (!sitl || sitl->efi_type != SIM::EFI_TYPE_MS) {
|
if (!sitl || sitl->efi_type != SIM::EFI_TYPE_MS) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
float rpm = sitl->state.rpm[0];
|
const float rpm = sitl->state.rpm[2];
|
||||||
|
|
||||||
|
tps = 0.9 * tps + 0.1 * (rpm / 7000) * 100;
|
||||||
|
|
||||||
table7.rpm = rpm;
|
table7.rpm = rpm;
|
||||||
table7.fuelload = 20;
|
table7.fuelload = 20;
|
||||||
table7.dwell = 2.0;
|
table7.dwell = 2.0;
|
||||||
table7.baro_hPa = 1000;
|
table7.baro_hPa = 1000;
|
||||||
table7.map_hPa = 895;
|
table7.map_hPa = 895;
|
||||||
table7.mat_cF = 3013;
|
table7.mat_cF = C_TO_F(AP::baro().get_temperature()) * 10;
|
||||||
table7.fuelPressure = 6280;
|
table7.fuelPressure = 6280;
|
||||||
table7.throttle_pos = 580;
|
table7.throttle_pos = tps * 10;
|
||||||
table7.ct_cF = 3940;
|
table7.ct_cF = 3940;
|
||||||
table7.afr_target1 = 148;
|
table7.afr_target1 = 148;
|
||||||
|
|
||||||
|
@ -96,6 +96,8 @@ private:
|
|||||||
uint8_t pad[128-67];
|
uint8_t pad[128-67];
|
||||||
uint16_t fuelPressure;
|
uint16_t fuelPressure;
|
||||||
} table7;
|
} table7;
|
||||||
|
|
||||||
|
float tps;
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user