Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Allow a ICE start even if disable while disarmed is set #25138

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduPlane/GCS_Mavlink.cpp
Expand Up @@ -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;
Expand Down
3 changes: 2 additions & 1 deletion ArduPlane/commands_logic.cpp
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_qloiter.cpp
Expand Up @@ -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
}
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.cpp
Expand Up @@ -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");
Expand Down
26 changes: 20 additions & 6 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Expand Up @@ -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;
}
Expand All @@ -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
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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 {
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_ICEngine/AP_ICEngine.h
Expand Up @@ -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);
Expand Down Expand Up @@ -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;

Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Mission/AP_Mission.cpp
Expand Up @@ -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:
Expand Down Expand Up @@ -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:
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Mission/AP_Mission.h
Expand Up @@ -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
WickedShell marked this conversation as resolved.
Show resolved Hide resolved
};

// NAV_SET_YAW_SPEED support
Expand Down