diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 2dba86c24eb19c..748bb8ef3f5466 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 = packet.param4 & 1; // disarmed start break; case MAV_CMD_NAV_PAYLOAD_PLACE: @@ -1751,6 +1752,7 @@ 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; + packet.param4 = cmd.content.do_engine_control.allow_disarmed_start; break; case MAV_CMD_NAV_PAYLOAD_PLACE: diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index c6b35b8fb09e82..e01c372ffa3c16 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