Browse Source

GCS_MAVLink: allow complete() call on subclasses to fail

Also terminate uploads if any error occurs fetching items
master
Peter Barker 6 years ago committed by Peter Barker
parent
commit
57528b94cf
  1. 4
      libraries/GCS_MAVLink/GCS_Common.cpp
  2. 10
      libraries/GCS_MAVLink/MissionItemProtocol.cpp
  3. 4
      libraries/GCS_MAVLink/MissionItemProtocol.h
  4. 3
      libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp
  5. 2
      libraries/GCS_MAVLink/MissionItemProtocol_Rally.h
  6. 3
      libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp
  7. 2
      libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.h

4
libraries/GCS_MAVLink/GCS_Common.cpp

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

10
libraries/GCS_MAVLink/MissionItemProtocol.cpp

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

4
libraries/GCS_MAVLink/MissionItemProtocol.h

@ -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 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 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() {}; virtual void timeout() {};
bool mavlink2_requirement_met(const GCS_MAVLINK &_link, const mavlink_message_t &msg) const; bool mavlink2_requirement_met(const GCS_MAVLINK &_link, const mavlink_message_t &msg) const;

3
libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp

@ -36,10 +36,11 @@ MAV_MISSION_RESULT MissionItemProtocol_Rally::append_item(const mavlink_mission_
return MAV_MISSION_ACCEPTED; 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"); _link.send_text(MAV_SEVERITY_INFO, "Rally points received");
AP::logger().Write_Rally(); AP::logger().Write_Rally();
return MAV_MISSION_ACCEPTED;
} }
bool MissionItemProtocol_Rally::clear_all_items() bool MissionItemProtocol_Rally::clear_all_items()

2
libraries/GCS_MAVLink/MissionItemProtocol_Rally.h

@ -9,7 +9,7 @@ public:
void truncate(const mavlink_mission_count_t &packet) override; void truncate(const mavlink_mission_count_t &packet) override;
MAV_MISSION_TYPE mission_type() const override { return MAV_MISSION_TYPE_RALLY; } 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; void timeout() override;
protected: protected:

3
libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp

@ -50,10 +50,11 @@ bool MissionItemProtocol_Waypoints::clear_all_items()
return mission.clear(); 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"); _link.send_text(MAV_SEVERITY_INFO, "Flight plan received");
AP::logger().Write_EntireMission(); AP::logger().Write_EntireMission();
return MAV_MISSION_ACCEPTED;
} }
MAV_MISSION_RESULT MissionItemProtocol_Waypoints::get_item(const GCS_MAVLINK &_link, MAV_MISSION_RESULT MissionItemProtocol_Waypoints::get_item(const GCS_MAVLINK &_link,

2
libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.h

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

Loading…
Cancel
Save