mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: factor out a check_receiving_cancel method
allow reuse of this logic
This commit is contained in:
parent
8ee7bf2dcb
commit
c0735d136c
|
@ -52,6 +52,29 @@ bool MissionItemProtocol::mavlink2_requirement_met(const GCS_MAVLINK &_link, con
|
|||
return false;
|
||||
}
|
||||
|
||||
// returns true if we are either not receiving, or we successfully
|
||||
// cancelled an existing upload:
|
||||
bool MissionItemProtocol::cancel_upload(const GCS_MAVLINK &_link, const mavlink_message_t &msg)
|
||||
{
|
||||
if (receiving) {
|
||||
// someone is already uploading a mission. If we are
|
||||
// receiving from someone then we will allow them to restart -
|
||||
// otherwise we deny.
|
||||
if (msg.sysid != dest_sysid || msg.compid != dest_compid) {
|
||||
// reject another upload until
|
||||
send_mission_ack(_link, msg, MAV_MISSION_DENIED);
|
||||
return false;
|
||||
}
|
||||
// the upload count may have changed; free resources and
|
||||
// allocate them again:
|
||||
free_upload_resources();
|
||||
receiving = false;
|
||||
link = nullptr;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void MissionItemProtocol::handle_mission_count(
|
||||
GCS_MAVLINK &_link,
|
||||
const mavlink_mission_count_t &packet,
|
||||
|
@ -61,21 +84,9 @@ void MissionItemProtocol::handle_mission_count(
|
|||
return;
|
||||
}
|
||||
|
||||
if (receiving) {
|
||||
// someone is already uploading a mission. If we are
|
||||
// receiving from someone then we will allow them to restart -
|
||||
// otherwise we deny.
|
||||
if (msg.sysid != dest_sysid || msg.compid != dest_compid) {
|
||||
// reject another upload until
|
||||
send_mission_ack(_link, msg, MAV_MISSION_DENIED);
|
||||
if (!cancel_upload(_link, msg)) {
|
||||
return;
|
||||
}
|
||||
// the upload count may have changed; free resources and
|
||||
// allocate them again:
|
||||
free_upload_resources();
|
||||
receiving = false;
|
||||
link = nullptr;
|
||||
}
|
||||
|
||||
if (packet.count > max_items()) {
|
||||
// FIXME: different items take up different storage space!
|
||||
|
|
|
@ -79,6 +79,10 @@ protected:
|
|||
|
||||
private:
|
||||
|
||||
// returns true if we are either not receiving, or we successfully
|
||||
// cancelled an existing upload:
|
||||
bool cancel_upload(const GCS_MAVLINK &_link, const mavlink_message_t &msg);
|
||||
|
||||
virtual void truncate(const mavlink_mission_count_t &packet) = 0;
|
||||
|
||||
uint16_t request_i; // request index
|
||||
|
|
Loading…
Reference in New Issue