Skip to content

Commit

Permalink
GCS_MAVLink: add warning if guided-mode-mission-requests are used
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Oct 29, 2024
1 parent e8c6093 commit bf3221c
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 1 deletion.
7 changes: 7 additions & 0 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -1038,8 +1038,10 @@ class GCS_MAVLINK

void send_distance_sensor(const class AP_RangeFinder_Backend *sensor, const uint8_t instance) const;

#if HAL_GCS_GUIDED_MISSION_REQUESTS_ENABLED
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) { return false; };
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) {};
#endif
void handle_common_mission_message(const mavlink_message_t &msg);

virtual void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) {};
Expand Down Expand Up @@ -1127,9 +1129,14 @@ class GCS_MAVLINK
// someone's doing SERIAL_CONTROL over mavlink)
bool _locked;

#if HAL_GCS_GUIDED_MISSION_REQUESTS_ENABLED
// handle a mission item int uploaded with current==2 or
// current==3, meaning go somewhere when in guided mode:
void handle_mission_item_guided_mode_request(const mavlink_message_t &msg, const mavlink_mission_item_int_t &mission_item_int);
// a timer so that we don't flood the GCS with deprecation
// warnings about people uploading missions with guided
uint32_t last_guided_mission_request_received_ms;
#endif
};

/// @class GCS
Expand Down
8 changes: 7 additions & 1 deletion libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -915,6 +915,12 @@ void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg)
#if AP_MISSION_ENABLED
void GCS_MAVLINK::handle_mission_item_guided_mode_request(const mavlink_message_t &msg, const mavlink_mission_item_int_t &mission_item_int)
{
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_guided_mission_request_received_ms > 60000) {
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Guided mode mission request received; use SET_POSITION_TARGET_GLOBAL_INT instead");
last_guided_mission_request_received_ms = now_ms;
}

const uint8_t current = mission_item_int.current;

struct AP_Mission::Mission_Command cmd = {};
Expand Down Expand Up @@ -971,7 +977,7 @@ void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg)
}
const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type;

#if AP_MISSION_ENABLED
#if HAL_GCS_GUIDED_MISSION_REQUESTS_ENABLED
const uint8_t current = mission_item_int.current;

if (type == MAV_MISSION_TYPE_MISSION && (current == 2 || current == 3)) {
Expand Down
9 changes: 9 additions & 0 deletions libraries/GCS_MAVLink/GCS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -139,3 +139,12 @@
#ifndef AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
#define AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED HAL_GCS_ENABLED
#endif

// CODE_REMOVAL
// ArduPilot can be commanded by upload of a mission item with the "current" field set to 2 (for position) or 3 (for just altitude. This behaviour is slated to be removed:
// ArduPilot 4.6 warns if the functionality is used
// ArduPilot 4.7 stops compiling support in
// ArduPilot 4.8 removes the code entirely
#ifndef HAL_GCS_GUIDED_MISSION_REQUESTS_ENABLED
#define HAL_GCS_GUIDED_MISSION_REQUESTS_ENABLED AP_MISSION_ENABLED
#endif

0 comments on commit bf3221c

Please sign in to comment.