Plane: fixed build with HAL_MINIMIZE_FEATURES enabled
thanks to PompeCukor for noticing
This commit is contained in:
parent
edd793c152
commit
fb061a225a
@ -334,11 +334,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HIL_SUPPORT
|
#ifndef HIL_SUPPORT
|
||||||
#if HAL_MINIMIZE_FEATURES
|
# define HIL_SUPPORT !HAL_MINIMIZE_FEATURES
|
||||||
# define HIL_SUPPORT DISABLED
|
|
||||||
#else
|
|
||||||
# define HIL_SUPPORT ENABLED
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
@ -350,11 +346,7 @@
|
|||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Payload Gripper
|
// Payload Gripper
|
||||||
#ifndef GRIPPER_ENABLED
|
#ifndef GRIPPER_ENABLED
|
||||||
#if HAL_MINIMIZE_FEATURES
|
#define GRIPPER_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
# define GRIPPER_ENABLED DISABLED
|
|
||||||
#else
|
|
||||||
# define GRIPPER_ENABLED ENABLED
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef STATS_ENABLED
|
#ifndef STATS_ENABLED
|
||||||
@ -362,11 +354,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef DEVO_TELEM_ENABLED
|
#ifndef DEVO_TELEM_ENABLED
|
||||||
#if HAL_MINIMIZE_FEATURES
|
#define DEVO_TELEM_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
#define DEVO_TELEM_ENABLED DISABLED
|
|
||||||
#else
|
|
||||||
#define DEVO_TELEM_ENABLED ENABLED
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef OSD_ENABLED
|
#ifndef OSD_ENABLED
|
||||||
@ -374,11 +362,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef SOARING_ENABLED
|
#ifndef SOARING_ENABLED
|
||||||
#if HAL_MINIMIZE_FEATURES
|
#define SOARING_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
#define SOARING_ENABLED DISABLED
|
|
||||||
#else
|
|
||||||
#define SOARING_ENABLED ENABLED
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef LANDING_GEAR_ENABLED
|
#ifndef LANDING_GEAR_ENABLED
|
||||||
|
@ -63,6 +63,7 @@ enum mode_reason_t {
|
|||||||
MODE_REASON_SOARING_IN_THERMAL,
|
MODE_REASON_SOARING_IN_THERMAL,
|
||||||
MODE_REASON_SOARING_THERMAL_ESTIMATE_DETERIORATED,
|
MODE_REASON_SOARING_THERMAL_ESTIMATE_DETERIORATED,
|
||||||
MODE_REASON_VTOL_FAILED_TRANSITION,
|
MODE_REASON_VTOL_FAILED_TRANSITION,
|
||||||
|
MODE_REASON_UNAVAILABLE,
|
||||||
};
|
};
|
||||||
|
|
||||||
// type of stick mixing enabled
|
// type of stick mixing enabled
|
||||||
|
@ -15,7 +15,9 @@ bool ModeAuto::_enter()
|
|||||||
// start or resume the mission, based on MIS_AUTORESET
|
// start or resume the mission, based on MIS_AUTORESET
|
||||||
plane.mission.start_or_resume();
|
plane.mission.start_or_resume();
|
||||||
|
|
||||||
|
#if SOARING_ENABLED == ENABLED
|
||||||
plane.g2.soaring_controller.init_cruising();
|
plane.g2.soaring_controller.init_cruising();
|
||||||
|
#endif
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -9,8 +9,10 @@ bool ModeCruise::_enter()
|
|||||||
plane.cruise_state.locked_heading = false;
|
plane.cruise_state.locked_heading = false;
|
||||||
plane.cruise_state.lock_timer_ms = 0;
|
plane.cruise_state.lock_timer_ms = 0;
|
||||||
|
|
||||||
|
#if SOARING_ENABLED == ENABLED
|
||||||
// for ArduSoar soaring_controller
|
// for ArduSoar soaring_controller
|
||||||
plane.g2.soaring_controller.init_cruising();
|
plane.g2.soaring_controller.init_cruising();
|
||||||
|
#endif
|
||||||
|
|
||||||
plane.set_target_altitude_current();
|
plane.set_target_altitude_current();
|
||||||
|
|
||||||
|
@ -7,8 +7,10 @@ bool ModeFBWB::_enter()
|
|||||||
plane.auto_throttle_mode = true;
|
plane.auto_throttle_mode = true;
|
||||||
plane.auto_navigation_mode = false;
|
plane.auto_navigation_mode = false;
|
||||||
|
|
||||||
|
#if SOARING_ENABLED == ENABLED
|
||||||
// for ArduSoar soaring_controller
|
// for ArduSoar soaring_controller
|
||||||
plane.g2.soaring_controller.init_cruising();
|
plane.g2.soaring_controller.init_cruising();
|
||||||
|
#endif
|
||||||
|
|
||||||
plane.set_target_altitude_current();
|
plane.set_target_altitude_current();
|
||||||
|
|
||||||
|
@ -8,10 +8,12 @@ bool ModeLoiter::_enter()
|
|||||||
plane.auto_navigation_mode = true;
|
plane.auto_navigation_mode = true;
|
||||||
plane.do_loiter_at_location();
|
plane.do_loiter_at_location();
|
||||||
|
|
||||||
|
#if SOARING_ENABLED == ENABLED
|
||||||
if (plane.g2.soaring_controller.is_active() && plane.g2.soaring_controller.suppress_throttle()) {
|
if (plane.g2.soaring_controller.is_active() && plane.g2.soaring_controller.suppress_throttle()) {
|
||||||
plane.g2.soaring_controller.init_thermalling();
|
plane.g2.soaring_controller.init_thermalling();
|
||||||
plane.g2.soaring_controller.get_target(plane.next_WP_loc); // ahead on flight path
|
plane.g2.soaring_controller.get_target(plane.next_WP_loc); // ahead on flight path
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -244,10 +244,10 @@ bool Plane::set_mode(Mode &new_mode, const mode_reason_t reason)
|
|||||||
}
|
}
|
||||||
|
|
||||||
#if !QAUTOTUNE_ENABLED
|
#if !QAUTOTUNE_ENABLED
|
||||||
if (&new_mode == plane.mode_qautotune) {
|
if (&new_mode == &plane.mode_qautotune) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO,"QAUTOTUNE disabled");
|
gcs().send_text(MAV_SEVERITY_INFO,"QAUTOTUNE disabled");
|
||||||
set_mode(plane.mode_qhover);
|
set_mode(plane.mode_qhover, MODE_REASON_UNAVAILABLE);
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user