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:
Peter Barker 2023-08-25 13:39:34 +10:00 committed by Peter Barker
parent 588364dad0
commit 7fff465251
1 changed files with 11 additions and 9 deletions

View File

@ -21,6 +21,8 @@
using namespace SITL; using namespace SITL;
#include <GCS_MAVLink/GCS.h>
/* /*
update engine state, returning power output from 0 to 1 update engine state, returning power output from 0 to 1
*/ */
@ -49,12 +51,12 @@ float ICEngine::update(const struct sitl_input &input)
} }
if (state.value != last_state.value) { if (state.value != last_state.value) {
printf("choke:%u starter:%u ignition:%u\n", GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: choke:%u starter:%u ignition:%u",
(unsigned)state.choke, (unsigned)state.choke,
(unsigned)state.starter, (unsigned)state.starter,
(unsigned)state.ignition); (unsigned)state.ignition);
} }
if (have_ignition && !state.ignition) { if (have_ignition && !state.ignition) {
// engine is off // engine is off
if (!state.starter) { if (!state.starter) {
@ -75,11 +77,11 @@ float ICEngine::update(const struct sitl_input &input)
} }
if (start_time_us == 0 && state.starter) { if (start_time_us == 0 && state.starter) {
if (throttle_demand > 0.2) { 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 { } else {
// start the motor // start the motor
if (start_time_us == 0) { if (start_time_us == 0) {
printf("Engine started\n"); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Engine started");
} }
start_time_us = now; 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); uint32_t starter_time_us = (now - start_time_us);
if (starter_time_us > 3000*1000UL && !overheat) { if (starter_time_us > 3000*1000UL && !overheat) {
overheat = true; overheat = true;
printf("Starter overheat\n"); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Starter overheat");
} }
} else { } else {
overheat = false; overheat = false;
@ -109,7 +111,7 @@ output:
engine_off: engine_off:
if (start_time_us != 0) { 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(); last_update_us = AP_HAL::micros64();
start_time_us = 0; start_time_us = 0;