Skip to content

Commit

Permalink
Copter: Fix AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Dec 2, 2023
1 parent 7f94ae6 commit e1a466f
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit e1a466f

Please sign in to comment.