mirror of https://github.com/ArduPilot/ardupilot
SITL: SIM_ICEngine sends diagnostics to GCS rather than stdout
makes it much easier to see what the simulated engine is doing
This commit is contained in:
parent
588364dad0
commit
7fff465251
|
@ -21,6 +21,8 @@
|
|||
|
||||
using namespace SITL;
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
/*
|
||||
update engine state, returning power output from 0 to 1
|
||||
*/
|
||||
|
@ -49,10 +51,10 @@ float ICEngine::update(const struct sitl_input &input)
|
|||
}
|
||||
|
||||
if (state.value != last_state.value) {
|
||||
printf("choke:%u starter:%u ignition:%u\n",
|
||||
(unsigned)state.choke,
|
||||
(unsigned)state.starter,
|
||||
(unsigned)state.ignition);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: choke:%u starter:%u ignition:%u",
|
||||
(unsigned)state.choke,
|
||||
(unsigned)state.starter,
|
||||
(unsigned)state.ignition);
|
||||
}
|
||||
|
||||
if (have_ignition && !state.ignition) {
|
||||
|
@ -75,11 +77,11 @@ float ICEngine::update(const struct sitl_input &input)
|
|||
}
|
||||
if (start_time_us == 0 && state.starter) {
|
||||
if (throttle_demand > 0.2) {
|
||||
printf("too much throttle to start: %.2f\n", throttle_demand);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: too much throttle to start: %.2f", throttle_demand);
|
||||
} else {
|
||||
// start the motor
|
||||
if (start_time_us == 0) {
|
||||
printf("Engine started\n");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Engine started");
|
||||
}
|
||||
start_time_us = now;
|
||||
}
|
||||
|
@ -88,7 +90,7 @@ float ICEngine::update(const struct sitl_input &input)
|
|||
uint32_t starter_time_us = (now - start_time_us);
|
||||
if (starter_time_us > 3000*1000UL && !overheat) {
|
||||
overheat = true;
|
||||
printf("Starter overheat\n");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Starter overheat");
|
||||
}
|
||||
} else {
|
||||
overheat = false;
|
||||
|
@ -109,7 +111,7 @@ output:
|
|||
|
||||
engine_off:
|
||||
if (start_time_us != 0) {
|
||||
printf("Engine stopped\n");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Engine stopped");
|
||||
}
|
||||
last_update_us = AP_HAL::micros64();
|
||||
start_time_us = 0;
|
||||
|
|
Loading…
Reference in New Issue