mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Plane: correct compilation when AP_Rally disabled
This commit is contained in:
parent
02932275ca
commit
98e2782851
@ -943,9 +943,11 @@ const AP_Param::Info Plane::var_info[] = {
|
|||||||
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
||||||
GOBJECT(mission, "MIS_", AP_Mission),
|
GOBJECT(mission, "MIS_", AP_Mission),
|
||||||
|
|
||||||
|
#if HAL_RALLY_ENABLED
|
||||||
// @Group: RALLY_
|
// @Group: RALLY_
|
||||||
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
|
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
|
||||||
GOBJECT(rally, "RALLY_", AP_Rally),
|
GOBJECT(rally, "RALLY_", AP_Rally),
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_NAVEKF2_AVAILABLE
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
// @Group: EK2_
|
// @Group: EK2_
|
||||||
|
@ -244,8 +244,14 @@ private:
|
|||||||
AP_OpticalFlow optflow;
|
AP_OpticalFlow optflow;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_RALLY_ENABLED
|
||||||
// Rally Ponints
|
// Rally Ponints
|
||||||
AP_Rally rally;
|
AP_Rally rally;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// returns a Location for a rally point or home; if
|
||||||
|
// HAL_RALLY_ENABLED is false, just home.
|
||||||
|
Location calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt_amsl_cm) const;
|
||||||
|
|
||||||
#if OSD_ENABLED || OSD_PARAM_ENABLED
|
#if OSD_ENABLED || OSD_PARAM_ENABLED
|
||||||
AP_OSD osd;
|
AP_OSD osd;
|
||||||
|
@ -344,7 +344,7 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)
|
|||||||
auto_state.next_wp_crosstrack = false;
|
auto_state.next_wp_crosstrack = false;
|
||||||
auto_state.crosstrack = false;
|
auto_state.crosstrack = false;
|
||||||
prev_WP_loc = current_loc;
|
prev_WP_loc = current_loc;
|
||||||
next_WP_loc = rally.calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm);
|
next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm);
|
||||||
setup_terrain_target_alt(next_WP_loc);
|
setup_terrain_target_alt(next_WP_loc);
|
||||||
set_target_altitude_location(next_WP_loc);
|
set_target_altitude_location(next_WP_loc);
|
||||||
|
|
||||||
@ -360,6 +360,17 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)
|
|||||||
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Location Plane::calc_best_rally_or_home_location(const Location &_current_loc, float rtl_home_alt_amsl_cm) const
|
||||||
|
{
|
||||||
|
#if HAL_RALLY_ENABLED
|
||||||
|
return plane.rally.calc_best_rally_or_home_location(_current_loc, rtl_home_alt_amsl_cm);
|
||||||
|
#else
|
||||||
|
Location destination = plane.home;
|
||||||
|
destination.set_alt_cm(rtl_home_alt_amsl_cm, Location::AltFrame::ABSOLUTE);
|
||||||
|
return destination;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
start a NAV_TAKEOFF command
|
start a NAV_TAKEOFF command
|
||||||
*/
|
*/
|
||||||
|
@ -75,7 +75,7 @@ void Plane::fence_check()
|
|||||||
|
|
||||||
Location loc;
|
Location loc;
|
||||||
if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
|
if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
|
||||||
loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm());
|
loc = calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm());
|
||||||
} else {
|
} else {
|
||||||
//return to fence return point, not a rally point
|
//return to fence return point, not a rally point
|
||||||
if (fence.get_return_altitude() > 0) {
|
if (fence.get_return_altitude() > 0) {
|
||||||
|
@ -17,8 +17,7 @@ bool ModeQRTL::_enter()
|
|||||||
int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL;
|
int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL;
|
||||||
if (quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
|
if (quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
|
||||||
// VTOL motors are active, either in VTOL flight or assisted flight
|
// VTOL motors are active, either in VTOL flight or assisted flight
|
||||||
Location destination = plane.rally.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm);
|
Location destination = plane.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm);
|
||||||
|
|
||||||
const float dist = plane.current_loc.get_distance(destination);
|
const float dist = plane.current_loc.get_distance(destination);
|
||||||
const float radius = get_VTOL_return_radius();
|
const float radius = get_VTOL_return_radius();
|
||||||
|
|
||||||
@ -122,7 +121,7 @@ void ModeQRTL::run()
|
|||||||
plane.prev_WP_loc = plane.current_loc;
|
plane.prev_WP_loc = plane.current_loc;
|
||||||
|
|
||||||
int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL;
|
int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL;
|
||||||
Location destination = plane.rally.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm);
|
Location destination = plane.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm);
|
||||||
const float dist = plane.current_loc.get_distance(destination);
|
const float dist = plane.current_loc.get_distance(destination);
|
||||||
const float radius = get_VTOL_return_radius();
|
const float radius = get_VTOL_return_radius();
|
||||||
if (dist < radius) {
|
if (dist < radius) {
|
||||||
|
Loading…
Reference in New Issue
Block a user