SITL: improve ICEngine simulation

This commit is contained in:
Andrew Tridgell 2016-07-23 17:36:10 +10:00
parent 02babb71b3
commit e73d43d4f9
4 changed files with 9 additions and 2 deletions

View File

@ -84,9 +84,12 @@ float ICEngine::update(const Aircraft::sitl_input &input)
} }
if (start_time_us != 0 && state.starter) { if (start_time_us != 0 && state.starter) {
uint32_t starter_time_us = (now - start_time_us); uint32_t starter_time_us = (now - start_time_us);
if (starter_time_us > 3000*1000UL) { if (starter_time_us > 3000*1000UL && !overheat) {
overheat = true;
printf("Starter overheat\n"); printf("Starter overheat\n");
} }
} else {
overheat = false;
} }
output: output:

View File

@ -54,5 +54,6 @@ private:
}; };
uint8_t value; uint8_t value;
} state, last_state; } state, last_state;
bool overheat:1;
}; };
} }

View File

@ -250,6 +250,9 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel
Vector3f force = getForce(aileron, elevator, rudder); Vector3f force = getForce(aileron, elevator, rudder);
rot_accel = getTorque(aileron, elevator, rudder, force); rot_accel = getTorque(aileron, elevator, rudder, force);
// simulate engine RPM
rpm1 = thrust * 7000;
// scale thrust to newtons // scale thrust to newtons
thrust *= thrust_scale; thrust *= thrust_scale;

View File

@ -98,7 +98,7 @@ protected:
bool reverse_elevator_rudder; bool reverse_elevator_rudder;
bool ice_engine; bool ice_engine;
ICEngine icengine{2, 4, 5, 6, 100}; ICEngine icengine{2, 14, 12, 13, 100};
float liftCoeff(float alpha) const; float liftCoeff(float alpha) const;
float dragCoeff(float alpha) const; float dragCoeff(float alpha) const;