Plane: Rename SOARING_ENABLED to HAL_SOARING_ENABLED and don't compare to ENABLED.

This commit is contained in:
Samuel Tabor 2020-09-23 09:16:45 +01:00 committed by Peter Barker
parent fe6c4d9290
commit 10111f92d5
16 changed files with 19 additions and 19 deletions

View File

@ -80,7 +80,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(Log_Write_Fast, 25, 300),
SCHED_TASK(update_logging1, 25, 300),
SCHED_TASK(update_logging2, 25, 300),
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
SCHED_TASK(update_soaring, 50, 400),
#endif
SCHED_TASK(parachute_check, 10, 200),

View File

@ -267,7 +267,7 @@ int16_t GCS_MAVLINK_Plane::vfr_hud_throttle() const
float GCS_MAVLINK_Plane::vfr_hud_climbrate() const
{
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
if (plane.g2.soaring_controller.is_active()) {
return plane.g2.soaring_controller.get_vario_reading();
}

View File

@ -1137,7 +1137,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
AP_SUBGROUPINFO(rc_channels, "RC", 7, ParametersG2, RC_Channels_Plane),
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
// @Group: SOAR_
// @Path: ../libraries/AP_Soaring/AP_Soaring.cpp
AP_SUBGROUPINFO(soaring_controller, "SOAR_", 8, ParametersG2, SoaringController),
@ -1300,7 +1300,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
ParametersG2::ParametersG2(void) :
ice_control(plane.rpm_sensor)
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
,soaring_controller(plane.TECS_controller, plane.aparm)
#endif
,button_ptr(&plane.button)

View File

@ -525,7 +525,7 @@ public:
// whether to enforce acceptance of packets only from sysid_my_gcs
AP_Int8 sysid_enforce;
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
// ArduSoar parameters
SoaringController soaring_controller;
#endif

View File

@ -280,7 +280,7 @@ private:
ModeQAcro mode_qacro;
ModeQAutotune mode_qautotune;
ModeTakeoff mode_takeoff;
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
ModeThermal mode_thermal;
#endif
@ -1072,7 +1072,7 @@ private:
#endif
// soaring.cpp
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
void update_soaring();
bool soaring_exit_heading_aligned() const;
void soaring_restore_mode(const char *reason, ModeReason modereason);

View File

@ -98,7 +98,7 @@ void RC_Channel_Plane::do_aux_function_crow_mode(AuxSwitchPos ch_flag)
void RC_Channel_Plane::do_aux_function_soaring_3pos(AuxSwitchPos ch_flag)
{
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
SoaringController::ActiveStatus desired_state = SoaringController::ActiveStatus::SOARING_DISABLED;
switch (ch_flag) {

View File

@ -61,7 +61,7 @@ void Plane::adjust_altitude_target()
landing.adjust_landing_slope_for_rangefinder_bump(rangefinder_state, prev_WP_loc, next_WP_loc, current_loc, auto_state.wp_distance, target_altitude.offset_cm);
} else if (landing.get_target_altitude_location(target_location)) {
set_target_altitude_location(target_location);
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
} else if (g2.soaring_controller.is_active() && g2.soaring_controller.get_throttle_suppressed()) {
// Reset target alt to current alt, to prevent large altitude errors when gliding.
set_target_altitude_location(current_loc);

View File

@ -74,7 +74,7 @@ Mode *Plane::mode_from_mode_num(const enum Mode::Number num)
ret = &mode_takeoff;
break;
case Mode::Number::THERMAL:
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
ret = &mode_thermal;
#endif
break;

View File

@ -524,7 +524,7 @@ protected:
bool _enter() override;
};
#if SOARING_ENABLED
#if HAL_SOARING_ENABLED
class ModeThermal: public Mode
{

View File

@ -23,7 +23,7 @@ bool ModeAuto::_enter()
}
}
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
plane.g2.soaring_controller.init_cruising();
#endif

View File

@ -9,7 +9,7 @@ bool ModeCruise::_enter()
locked_heading = false;
lock_timer_ms = 0;
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
// for ArduSoar soaring_controller
plane.g2.soaring_controller.init_cruising();
#endif

View File

@ -7,7 +7,7 @@ bool ModeFBWB::_enter()
plane.auto_throttle_mode = true;
plane.auto_navigation_mode = false;
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
// for ArduSoar soaring_controller
plane.g2.soaring_controller.init_cruising();
#endif

View File

@ -1,7 +1,7 @@
#include "mode.h"
#include "Plane.h"
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
bool ModeThermal::_enter()
{

View File

@ -338,7 +338,7 @@ void Plane::update_fbwb_speed_height(void)
set_target_altitude_current();
}
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
if (g2.soaring_controller.is_active()) {
if (g2.soaring_controller.get_throttle_suppressed()) {
// we're in soaring mode with throttle suppressed

View File

@ -1,6 +1,6 @@
#include "Plane.h"
#if SOARING_ENABLED == ENABLED
#if HAL_SOARING_ENABLED
/*
* ArduSoar support function

View File

@ -16,8 +16,8 @@
#include "Variometer.h"
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
#ifndef SOARING_ENABLED
#define SOARING_ENABLED !HAL_MINIMIZE_FEATURES
#ifndef HAL_SOARING_ENABLED
#define HAL_SOARING_ENABLED !HAL_MINIMIZE_FEATURES
#endif
#define INITIAL_THERMAL_STRENGTH 2.0