Copter: Fix AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
This commit is contained in:
parent
c61ee15c1f
commit
60ceaec901
@ -1515,14 +1515,14 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const
|
||||
switch (next_cmd.id) {
|
||||
case MAV_CMD_NAV_WAYPOINT:
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
case MAV_CMD_NAV_LOITER_TIME:
|
||||
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
|
||||
case MAV_CMD_NAV_PAYLOAD_PLACE: {
|
||||
case MAV_CMD_NAV_PAYLOAD_PLACE:
|
||||
#endif
|
||||
case MAV_CMD_NAV_LOITER_TIME: {
|
||||
const Location dest_loc = loc_from_cmd(current_cmd, default_loc);
|
||||
const Location next_dest_loc = loc_from_cmd(next_cmd, dest_loc);
|
||||
return wp_nav->set_wp_destination_next_loc(next_dest_loc);
|
||||
}
|
||||
#endif
|
||||
case MAV_CMD_NAV_SPLINE_WAYPOINT: {
|
||||
// get spline's location and next location from command and send to wp_nav
|
||||
Location next_dest_loc, next_next_dest_loc;
|
||||
|
Loading…
Reference in New Issue
Block a user