mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: allow VTOL_TAKEOFF and VTOL_LAND as synonyms
this allows is_takeoff_next() to be in common, and reduces confusion if user selects VTOL_TAKEOFF in a GCS mission editor
This commit is contained in:
parent
6634b0926e
commit
009f3e9ea8
@ -743,6 +743,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||||||
{
|
{
|
||||||
switch(packet.command) {
|
switch(packet.command) {
|
||||||
|
|
||||||
|
case MAV_CMD_NAV_VTOL_TAKEOFF:
|
||||||
case MAV_CMD_NAV_TAKEOFF: {
|
case MAV_CMD_NAV_TAKEOFF: {
|
||||||
// param3 : horizontal navigation by pilot acceptable
|
// param3 : horizontal navigation by pilot acceptable
|
||||||
// param4 : yaw angle (not supported)
|
// param4 : yaw angle (not supported)
|
||||||
@ -778,6 +779,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||||||
}
|
}
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
|
||||||
|
case MAV_CMD_NAV_VTOL_LAND:
|
||||||
case MAV_CMD_NAV_LAND:
|
case MAV_CMD_NAV_LAND:
|
||||||
if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) {
|
if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) {
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
@ -528,6 +528,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
///
|
///
|
||||||
/// navigation commands
|
/// navigation commands
|
||||||
///
|
///
|
||||||
|
case MAV_CMD_NAV_VTOL_TAKEOFF:
|
||||||
case MAV_CMD_NAV_TAKEOFF: // 22
|
case MAV_CMD_NAV_TAKEOFF: // 22
|
||||||
do_takeoff(cmd);
|
do_takeoff(cmd);
|
||||||
break;
|
break;
|
||||||
@ -536,6 +537,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
do_nav_wp(cmd);
|
do_nav_wp(cmd);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_NAV_VTOL_LAND:
|
||||||
case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
|
case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
|
||||||
do_land(cmd);
|
do_land(cmd);
|
||||||
break;
|
break;
|
||||||
@ -764,6 +766,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
//
|
//
|
||||||
// navigation commands
|
// navigation commands
|
||||||
//
|
//
|
||||||
|
case MAV_CMD_NAV_VTOL_TAKEOFF:
|
||||||
case MAV_CMD_NAV_TAKEOFF:
|
case MAV_CMD_NAV_TAKEOFF:
|
||||||
cmd_complete = verify_takeoff();
|
cmd_complete = verify_takeoff();
|
||||||
break;
|
break;
|
||||||
@ -772,6 +775,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
cmd_complete = verify_nav_wp(cmd);
|
cmd_complete = verify_nav_wp(cmd);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_NAV_VTOL_LAND:
|
||||||
case MAV_CMD_NAV_LAND:
|
case MAV_CMD_NAV_LAND:
|
||||||
cmd_complete = verify_land();
|
cmd_complete = verify_land();
|
||||||
break;
|
break;
|
||||||
@ -1284,10 +1288,12 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const
|
|||||||
get_spline_from_cmd(next_cmd, default_loc, next_dest_loc, next_next_dest_loc, next_next_dest_loc_is_spline);
|
get_spline_from_cmd(next_cmd, default_loc, next_dest_loc, next_next_dest_loc, next_next_dest_loc_is_spline);
|
||||||
return wp_nav->set_spline_destination_next_loc(next_dest_loc, next_next_dest_loc, next_next_dest_loc_is_spline);
|
return wp_nav->set_spline_destination_next_loc(next_dest_loc, next_next_dest_loc, next_next_dest_loc_is_spline);
|
||||||
}
|
}
|
||||||
|
case MAV_CMD_NAV_VTOL_LAND:
|
||||||
case MAV_CMD_NAV_LAND:
|
case MAV_CMD_NAV_LAND:
|
||||||
// stop because we may change between rel,abs and terrain alt types
|
// stop because we may change between rel,abs and terrain alt types
|
||||||
case MAV_CMD_NAV_LOITER_TURNS:
|
case MAV_CMD_NAV_LOITER_TURNS:
|
||||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||||
|
case MAV_CMD_NAV_VTOL_TAKEOFF:
|
||||||
case MAV_CMD_NAV_TAKEOFF:
|
case MAV_CMD_NAV_TAKEOFF:
|
||||||
// always stop for RTL and takeoff commands
|
// always stop for RTL and takeoff commands
|
||||||
default:
|
default:
|
||||||
|
Loading…
Reference in New Issue
Block a user