mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: correct compilation when AUTO/RTL are disabled
This commit is contained in:
parent
2783257aa4
commit
af53f9ce64
@ -229,6 +229,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||||||
#endif // HELI_FRAME
|
#endif // HELI_FRAME
|
||||||
|
|
||||||
// checks when using range finder for RTL
|
// checks when using range finder for RTL
|
||||||
|
#if MODE_RTL_ENABLED == ENABLED
|
||||||
if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) {
|
if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) {
|
||||||
// get terrain source from wpnav
|
// get terrain source from wpnav
|
||||||
switch (copter.wp_nav->get_terrain_source()) {
|
switch (copter.wp_nav->get_terrain_source()) {
|
||||||
@ -267,6 +268,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// check adsb avoidance failsafe
|
// check adsb avoidance failsafe
|
||||||
#if HAL_ADSB_ENABLED
|
#if HAL_ADSB_ENABLED
|
||||||
|
@ -697,11 +697,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
case MAV_CMD_DO_LAND_START:
|
case MAV_CMD_DO_LAND_START:
|
||||||
if (copter.mode_auto.mission.jump_to_landing_sequence() && copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
|
if (copter.mode_auto.mission.jump_to_landing_sequence() && copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
#endif
|
||||||
|
|
||||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||||
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
|
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
|
||||||
|
Loading…
Reference in New Issue
Block a user