Skip to content

Commit

Permalink
AP_Mission: Support disarmed starts in engine control
Browse files Browse the repository at this point in the history
  • Loading branch information
WickedShell committed Sep 28, 2023
1 parent 545e44c commit 4856ab6
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 0 deletions.
2 changes: 2 additions & 0 deletions libraries/AP_Mission/AP_Mission.cpp
Original file line number Diff line number Diff line change
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 = packet.param4 & 1; // disarmed start
break;

case MAV_CMD_NAV_PAYLOAD_PLACE:
Expand Down Expand Up @@ -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:
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Mission/AP_Mission.h
Original file line number Diff line number Diff line change
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
};

// NAV_SET_YAW_SPEED support
Expand Down

0 comments on commit 4856ab6

Please sign in to comment.