GCS_MAVLink: allow complete() call on subclasses to fail

Also terminate uploads if any error occurs fetching items
This commit is contained in:
Peter Barker 2019-08-07 10:23:05 +10:00 committed by Peter Barker
parent cfd7e05257
commit 57528b94cf
7 changed files with 17 additions and 11 deletions

View File

@ -14,6 +14,8 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "GCS.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Arming/AP_Arming.h>
@ -36,8 +38,6 @@
#include <AP_OpticalFlow/OpticalFlow.h>
#include <AP_Baro/AP_Baro.h>
#include "GCS.h"
#include <stdio.h>
#if HAL_RCINPUT_WITH_AP_RADIO

View File

@ -74,8 +74,8 @@ void MissionItemProtocol::handle_mission_count(
if (packet.count == 0) {
// no requests to send...
send_mission_ack(_link, msg, MAV_MISSION_ACCEPTED);
complete(_link);
const MAV_MISSION_RESULT result = complete(_link);
send_mission_ack(_link, msg, result);
return;
}
@ -233,6 +233,8 @@ void MissionItemProtocol::handle_mission_item(const mavlink_message_t &msg, cons
}
if (result != MAV_MISSION_ACCEPTED) {
send_mission_ack(msg, result);
receiving = false;
link = nullptr;
return;
}
@ -241,8 +243,8 @@ void MissionItemProtocol::handle_mission_item(const mavlink_message_t &msg, cons
request_i++;
if (request_i > request_last) {
send_mission_ack(msg, MAV_MISSION_ACCEPTED);
complete(*link);
const MAV_MISSION_RESULT complete_result = complete(*link);
send_mission_ack(msg, complete_result);
receiving = false;
link = nullptr;
return;

View File

@ -106,7 +106,9 @@ private:
virtual MAV_MISSION_RESULT replace_item(const mavlink_mission_item_int_t &mission_item_int) = 0;
virtual MAV_MISSION_RESULT append_item(const mavlink_mission_item_int_t &mission_item_int) = 0;
virtual void complete(const GCS_MAVLINK &_link) {};
virtual MAV_MISSION_RESULT complete(const GCS_MAVLINK &_link) {
return MAV_MISSION_ACCEPTED;
};
virtual void timeout() {};
bool mavlink2_requirement_met(const GCS_MAVLINK &_link, const mavlink_message_t &msg) const;

View File

@ -36,10 +36,11 @@ MAV_MISSION_RESULT MissionItemProtocol_Rally::append_item(const mavlink_mission_
return MAV_MISSION_ACCEPTED;
}
void MissionItemProtocol_Rally::complete(const GCS_MAVLINK &_link)
MAV_MISSION_RESULT MissionItemProtocol_Rally::complete(const GCS_MAVLINK &_link)
{
_link.send_text(MAV_SEVERITY_INFO, "Rally points received");
AP::logger().Write_Rally();
return MAV_MISSION_ACCEPTED;
}
bool MissionItemProtocol_Rally::clear_all_items()

View File

@ -9,7 +9,7 @@ public:
void truncate(const mavlink_mission_count_t &packet) override;
MAV_MISSION_TYPE mission_type() const override { return MAV_MISSION_TYPE_RALLY; }
void complete(const GCS_MAVLINK &_link) override;
MAV_MISSION_RESULT complete(const GCS_MAVLINK &_link) override;
void timeout() override;
protected:

View File

@ -50,10 +50,11 @@ bool MissionItemProtocol_Waypoints::clear_all_items()
return mission.clear();
}
void MissionItemProtocol_Waypoints::complete(const GCS_MAVLINK &_link)
MAV_MISSION_RESULT MissionItemProtocol_Waypoints::complete(const GCS_MAVLINK &_link)
{
_link.send_text(MAV_SEVERITY_INFO, "Flight plan received");
AP::logger().Write_EntireMission();
return MAV_MISSION_ACCEPTED;
}
MAV_MISSION_RESULT MissionItemProtocol_Waypoints::get_item(const GCS_MAVLINK &_link,

View File

@ -16,7 +16,7 @@ public:
// complete() is called by the base class after all waypoints have
// been received. _link is the link which the last item was
// transfered on.
void complete(const GCS_MAVLINK &_link) override;
MAV_MISSION_RESULT complete(const GCS_MAVLINK &_link) override;
// timeout() is called by the base class in the case that the GCS
// does not transfer all waypoints to the vehicle.
void timeout() override;