From f7e2c798857dcd895934da4814b74331baa4c9e4 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 19 Jul 2021 16:53:50 -0700 Subject: [PATCH 1/4] AP_ICEngine: Add a flag to allow starting the engine while disarmed --- libraries/AP_ICEngine/AP_ICEngine.cpp | 26 ++++++++++++++++++++------ libraries/AP_ICEngine/AP_ICEngine.h | 4 +++- 2 files changed, 23 insertions(+), 7 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index b5b85d38dd4c7..ade41a1578ad4 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -238,6 +238,11 @@ void AP_ICEngine::update(void) should_run = true; } else if (start_chan_last_value <= RC_Channel::AUX_PWM_TRIGGER_LOW) { should_run = false; + + // clear the single start flag now that we will be stopping the engine + if (state != ICE_OFF) { + allow_single_start_while_disarmed = false; + } } else if (state != ICE_OFF) { should_run = true; } @@ -247,9 +252,16 @@ void AP_ICEngine::update(void) should_run = false; } - if (option_set(Options::NO_RUNNING_WHILE_DISARMED) && !hal.util->get_soft_armed()) { - // disable the engine if disarmed - should_run = false; + if (option_set(Options::NO_RUNNING_WHILE_DISARMED)) { + if (hal.util->get_soft_armed()) { + // clear the disarmed start flag, as we are now armed, if we disarm again we expect the engine to stop + allow_single_start_while_disarmed = false; + } else { + // check if we are blocking disarmed starts + if (!allow_single_start_while_disarmed) { + should_run = false; + } + } } #if HAL_PARACHUTE_ENABLED @@ -464,15 +476,18 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle return false; } - /* handle DO_ENGINE_CONTROL messages via MAVLink or mission */ -bool AP_ICEngine::engine_control(float start_control, float cold_start, float height_delay) +bool AP_ICEngine::engine_control(float start_control, float cold_start, float height_delay, uint32_t flags) { if (!enable) { return false; } + + // always update the start while disarmed flag + allow_single_start_while_disarmed = (flags & ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED) != 0; + if (start_control <= 0) { state = ICE_OFF; return true; @@ -576,7 +591,6 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle) #endif // AP_RPM_ENABLED } - // singleton instance. Should only ever be set in the constructor. AP_ICEngine *AP_ICEngine::_singleton; namespace AP { diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 1c243dd88fa2c..743f8ccb9973a 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -52,7 +52,7 @@ class AP_ICEngine { ICE_State get_state(void) const { return !enable?ICE_DISABLED:state; } // handle DO_ENGINE_CONTROL messages via MAVLink or mission - bool engine_control(float start_control, float cold_start, float height_delay); + bool engine_control(float start_control, float cold_start, float height_delay, uint32_t flags); // update min throttle for idle governor void update_idle_governor(int8_t &min_throttle); @@ -138,6 +138,8 @@ class AP_ICEngine { // we are waiting for valid height data bool height_pending:1; + bool allow_single_start_while_disarmed; + // idle governor float idle_governor_integrator; From 0df854754f68d4646b6fd06d29b5b8737f6a9916 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 19 Jul 2021 16:54:33 -0700 Subject: [PATCH 2/4] ArduPlane: Pass the 4th parameter to ICE for engine start --- ArduPlane/GCS_Mavlink.cpp | 2 +- ArduPlane/commands_logic.cpp | 3 ++- ArduPlane/mode_qloiter.cpp | 2 +- ArduPlane/quadplane.cpp | 2 +- 4 files changed, 5 insertions(+), 4 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index efb77d48129e5..52a4b875906ac 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -977,7 +977,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in #if AP_ICENGINE_ENABLED case MAV_CMD_DO_ENGINE_CONTROL: - if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3)) { + if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3, (uint32_t)packet.param4)) { return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED; diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 79887fabdeb3c..52152ec61579e 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -199,7 +199,8 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_DO_ENGINE_CONTROL: plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_control, cmd.content.do_engine_control.cold_start, - cmd.content.do_engine_control.height_delay_cm*0.01f); + cmd.content.do_engine_control.height_delay_cm*0.01f, + cmd.content.do_engine_control.allow_disarmed_start); break; #endif diff --git a/ArduPlane/mode_qloiter.cpp b/ArduPlane/mode_qloiter.cpp index 50dd8deea749b..2eea970c58be3 100644 --- a/ArduPlane/mode_qloiter.cpp +++ b/ArduPlane/mode_qloiter.cpp @@ -104,7 +104,7 @@ void ModeQLoiter::run() #if AP_ICENGINE_ENABLED // cut IC engine if enabled if (quadplane.land_icengine_cut != 0) { - plane.g2.ice_control.engine_control(0, 0, 0); + plane.g2.ice_control.engine_control(0, 0, 0, false); } #endif // AP_ICENGINE_ENABLED } diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index d6a72bc5a6b4b..fbb1b3c9fe27f 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3610,7 +3610,7 @@ bool QuadPlane::verify_vtol_land(void) #if AP_ICENGINE_ENABLED // cut IC engine if enabled if (land_icengine_cut != 0) { - plane.g2.ice_control.engine_control(0, 0, 0); + plane.g2.ice_control.engine_control(0, 0, 0, false); } #endif // AP_ICENGINE_ENABLED gcs().send_text(MAV_SEVERITY_INFO,"Land final started"); From a67782fc1fc385e5e20d2693a7898e9468f2e01d Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 28 Sep 2023 11:51:37 -0700 Subject: [PATCH 3/4] AP_Mission: Support disarmed starts in engine control --- libraries/AP_Mission/AP_Mission.cpp | 4 ++++ libraries/AP_Mission/AP_Mission.h | 1 + 2 files changed, 5 insertions(+) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 2dba86c24eb19..617d8a77aa1bf 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -1247,6 +1247,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ cmd.content.do_engine_control.start_control = (packet.param1>0); cmd.content.do_engine_control.cold_start = (packet.param2>0); cmd.content.do_engine_control.height_delay_cm = packet.param3*100; + cmd.content.do_engine_control.allow_disarmed_start = (((uint32_t)packet.param4) & ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED) != 0; break; case MAV_CMD_NAV_PAYLOAD_PLACE: @@ -1751,6 +1752,9 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.param1 = cmd.content.do_engine_control.start_control?1:0; packet.param2 = cmd.content.do_engine_control.cold_start?1:0; packet.param3 = cmd.content.do_engine_control.height_delay_cm*0.01f; + if (cmd.content.do_engine_control.allow_disarmed_start) { + packet.param4 = ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED; + } break; case MAV_CMD_NAV_PAYLOAD_PLACE: diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index c6b35b8fb09e8..e01c372ffa3c1 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -203,6 +203,7 @@ class AP_Mission bool start_control; // start or stop engine bool cold_start; // use cold start procedure uint16_t height_delay_cm; // height delay for start + bool allow_disarmed_start; // allow starting the engine while disarmed }; // NAV_SET_YAW_SPEED support From 7eff6f68d2603c949563845affc52f3d00d0dd64 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Fri, 20 Oct 2023 11:33:58 -0700 Subject: [PATCH 4/4] mavlink: update submodule for ENGINE_CONTROL_OPTIONS --- modules/mavlink | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/mavlink b/modules/mavlink index 6a8b6412b4f9b..dccd8555cd601 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 6a8b6412b4f9b63b5fe82d608e6a18cf0e98de0c +Subproject commit dccd8555cd601467dc793ea9abf85caa63c0a9e8