|
|
|
@ -516,6 +516,12 @@ void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg) const
@@ -516,6 +516,12 @@ void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg) const
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
handle a MISSION_SET_CURRENT mavlink packet |
|
|
|
|
|
|
|
|
|
Note that there exists a relatively new mavlink DO command, |
|
|
|
|
MAV_CMD_DO_SET_MISSION_CURRENT which provides an acknowledgement |
|
|
|
|
that the command has been received, rather than the GCS having to |
|
|
|
|
rely on getting back an identical sequence number as some currently |
|
|
|
|
do. |
|
|
|
|
*/ |
|
|
|
|
void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg) |
|
|
|
|
{ |
|
|
|
@ -3788,6 +3794,29 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_can(const mavlink_command_long_
@@ -3788,6 +3794,29 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_can(const mavlink_command_long_
|
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// changes the current waypoint; at time of writing GCS
|
|
|
|
|
// implementations use the mavlink message MISSION_SET_CURRENT to set
|
|
|
|
|
// the current waypoint, rather than this DO command. It is hoped we
|
|
|
|
|
// can move to this command in the future to avoid acknowledgement
|
|
|
|
|
// issues with MISSION_SET_CURRENT
|
|
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_command_long_t &packet) |
|
|
|
|
{ |
|
|
|
|
AP_Mission *mission = AP::mission(); |
|
|
|
|
if (mission == nullptr) { |
|
|
|
|
return MAV_RESULT_UNSUPPORTED; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
const uint32_t seq = (uint32_t)packet.param1; |
|
|
|
|
if (!mission->set_current_cmd(seq)) { |
|
|
|
|
return MAV_RESULT_FAILED; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// volunteer the new current waypoint for all listeners
|
|
|
|
|
send_message(MSG_CURRENT_WAYPOINT); |
|
|
|
|
|
|
|
|
|
return MAV_RESULT_ACCEPTED; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_long_t &packet) |
|
|
|
|
{ |
|
|
|
|
const uint16_t battery_mask = packet.param1; |
|
|
|
@ -4059,6 +4088,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
@@ -4059,6 +4088,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|
|
|
|
result = handle_command_preflight_calibration(packet); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_MISSION_CURRENT: |
|
|
|
|
result = handle_command_do_set_mission_current(packet); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_BATTERY_RESET: |
|
|
|
|
result = handle_command_battery_reset(packet); |
|
|
|
|
break; |
|
|
|
|