From 2be4c0e3f5d3f83c3a92fdfd689cde75cab7da89 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 28 Oct 2023 17:06:45 +1100 Subject: [PATCH] Copter: correct defines around using payload place functionality we need support for the actual payload place flight behaviour as well as the navigation item support --- ArduCopter/mode.h | 2 +- ArduCopter/mode_auto.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 7e36797d64..3de08e4766 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -501,7 +501,7 @@ public: NAVGUIDED, LOITER, LOITER_TO_ALT, -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED NAV_PAYLOAD_PLACE, #endif NAV_SCRIPT_TIME, diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 1f769d93ab..b79b008c2e 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -149,7 +149,7 @@ void ModeAuto::run() loiter_to_alt_run(); break; -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED case SubMode::NAV_PAYLOAD_PLACE: payload_place.run(); break; @@ -661,7 +661,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) do_nav_delay(cmd); break; -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint do_payload_place(cmd); break; @@ -871,7 +871,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) cmd_complete = verify_land(); break; -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED case MAV_CMD_NAV_PAYLOAD_PLACE: cmd_complete = payload_place.verify(); break; @@ -1923,7 +1923,7 @@ void ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd) } #endif -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED // do_payload_place - initiate placing procedure void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd) {