mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
4b4c6e8696
commit
2be4c0e3f5
|
@ -501,7 +501,7 @@ public:
|
||||||
NAVGUIDED,
|
NAVGUIDED,
|
||||||
LOITER,
|
LOITER,
|
||||||
LOITER_TO_ALT,
|
LOITER_TO_ALT,
|
||||||
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
|
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
|
||||||
NAV_PAYLOAD_PLACE,
|
NAV_PAYLOAD_PLACE,
|
||||||
#endif
|
#endif
|
||||||
NAV_SCRIPT_TIME,
|
NAV_SCRIPT_TIME,
|
||||||
|
|
|
@ -149,7 +149,7 @@ void ModeAuto::run()
|
||||||
loiter_to_alt_run();
|
loiter_to_alt_run();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
|
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
|
||||||
case SubMode::NAV_PAYLOAD_PLACE:
|
case SubMode::NAV_PAYLOAD_PLACE:
|
||||||
payload_place.run();
|
payload_place.run();
|
||||||
break;
|
break;
|
||||||
|
@ -661,7 +661,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
||||||
do_nav_delay(cmd);
|
do_nav_delay(cmd);
|
||||||
break;
|
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
|
case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint
|
||||||
do_payload_place(cmd);
|
do_payload_place(cmd);
|
||||||
break;
|
break;
|
||||||
|
@ -871,7 +871,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
|
||||||
cmd_complete = verify_land();
|
cmd_complete = verify_land();
|
||||||
break;
|
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:
|
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
||||||
cmd_complete = payload_place.verify();
|
cmd_complete = payload_place.verify();
|
||||||
break;
|
break;
|
||||||
|
@ -1923,7 +1923,7 @@ void ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
|
||||||
}
|
}
|
||||||
#endif
|
#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
|
// do_payload_place - initiate placing procedure
|
||||||
void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd)
|
void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue