Skip to content

Commit

Permalink
Copter: correct defines around using payload place functionality
Browse files Browse the repository at this point in the history
we need support for the actual payload place flight behaviour as well as the navigation item support
  • Loading branch information
peterbarker authored and tridge committed Oct 31, 2023
1 parent 4b4c6e8 commit 2be4c0e
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -501,7 +501,7 @@ class ModeAuto : public Mode {
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,
Expand Down
8 changes: 4 additions & 4 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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)
{
Expand Down

0 comments on commit 2be4c0e

Please sign in to comment.