From 3391393d86a814304b8926428e20f7292dbfead6 Mon Sep 17 00:00:00 2001 From: Tim Tuxworth Date: Fri, 23 Aug 2024 11:35:04 -0600 Subject: [PATCH] ArduPlane: Scripted follow in Plane --- ArduPlane/GCS_Mavlink.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index eeb604f47855fa..efdf18113ed513 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -989,19 +989,26 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl float new_target_heading = radians(wrap_180(packet.param2)); // Default value = no heading track + /* requires ardupilot_mega.xml change if ( int(packet.param1) == HEADING_TYPE_DEFAULT) { plane.guided_state.target_heading_type = GUIDED_HEADING_NONE; return MAV_RESULT_ACCEPTED; // course over ground - } else if ( int(packet.param1) == HEADING_TYPE_COURSE_OVER_GROUND) { // compare as nearest int + } else + */ + if ( int(packet.param1) == HEADING_TYPE_COURSE_OVER_GROUND) { // compare as nearest int plane.guided_state.target_heading_type = GUIDED_HEADING_COG; plane.prev_WP_loc = plane.current_loc; // normal vehicle heading } else if (int(packet.param1) == HEADING_TYPE_HEADING) { // compare as nearest int plane.guided_state.target_heading_type = GUIDED_HEADING_HEADING; } else { + // fudge for now if we get an invalid result we assume it's "DEFAULT" + plane.guided_state.target_heading_type = GUIDED_HEADING_NONE; + return MAV_RESULT_ACCEPTED; + // MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters). - return MAV_RESULT_DENIED; + // return MAV_RESULT_DENIED; } plane.g2.guidedHeading.reset_I(); @@ -1011,8 +1018,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl plane.guided_state.target_heading_time_ms = AP_HAL::millis(); return MAV_RESULT_ACCEPTED; } -#endif // OFFBOARD_GUIDED == ENABLED - } // anything else ... return MAV_RESULT_UNSUPPORTED;