ArduPlane: Pass the 4th parameter to ICE for engine start

This commit is contained in:
Michael du Breuil 2021-07-19 16:54:33 -07:00 committed by WickedShell
parent 9486bf2b9c
commit b630efd4db
4 changed files with 5 additions and 4 deletions

View File

@ -977,7 +977,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
#if AP_ICENGINE_ENABLED #if AP_ICENGINE_ENABLED
case MAV_CMD_DO_ENGINE_CONTROL: 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_FAILED;
} }
return MAV_RESULT_ACCEPTED; return MAV_RESULT_ACCEPTED;

View File

@ -199,7 +199,8 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_DO_ENGINE_CONTROL: case MAV_CMD_DO_ENGINE_CONTROL:
plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_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.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; break;
#endif #endif

View File

@ -104,7 +104,7 @@ void ModeQLoiter::run()
#if AP_ICENGINE_ENABLED #if AP_ICENGINE_ENABLED
// cut IC engine if enabled // cut IC engine if enabled
if (quadplane.land_icengine_cut != 0) { 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 #endif // AP_ICENGINE_ENABLED
} }

View File

@ -3610,7 +3610,7 @@ bool QuadPlane::verify_vtol_land(void)
#if AP_ICENGINE_ENABLED #if AP_ICENGINE_ENABLED
// cut IC engine if enabled // cut IC engine if enabled
if (land_icengine_cut != 0) { 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 #endif // AP_ICENGINE_ENABLED
gcs().send_text(MAV_SEVERITY_INFO,"Land final started"); gcs().send_text(MAV_SEVERITY_INFO,"Land final started");