Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove ENABLE/ENABLED from Plane #27728

Merged
merged 7 commits into from
Aug 5, 2024
Merged
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -559,7 +559,7 @@ void Plane::update_alt()

// low pass the sink rate to take some of the noise out
auto_state.sink_rate = 0.8f * auto_state.sink_rate + 0.2f*sink_rate;
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
parachute.set_sink_rate(auto_state.sink_rate);
#endif

Expand Down
10 changes: 5 additions & 5 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -878,8 +878,8 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet)
{
switch(packet.command) {
#if OFFBOARD_GUIDED == ENABLED

#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
case MAV_CMD_GUIDED_CHANGE_SPEED: {
// command is only valid in guided mode
if (plane.control_mode != &plane.mode_guided) {
Expand Down Expand Up @@ -1008,7 +1008,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl
plane.guided_state.target_heading_time_ms = AP_HAL::millis();
return MAV_RESULT_ACCEPTED;
}
#endif // OFFBOARD_GUIDED == ENABLED
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED


}
Expand Down Expand Up @@ -1054,7 +1054,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
case MAV_CMD_DO_CHANGE_SPEED:
return handle_command_DO_CHANGE_SPEED(packet);

#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
case MAV_CMD_DO_PARACHUTE:
return handle_MAV_CMD_DO_PARACHUTE(packet);
#endif
Expand Down Expand Up @@ -1182,7 +1182,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_co
return MAV_RESULT_ACCEPTED;
}

#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
{
// configure or release parachute
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ void Plane::Log_Write_Control_Tuning()
logger.WriteBlock(&pkt, sizeof(pkt));
}

#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
struct PACKED log_OFG_Guided {
LOG_PACKET_HEADER;
uint64_t time_us;
Expand Down Expand Up @@ -265,7 +265,7 @@ void Plane::Log_Write_RC(void)

void Plane::Log_Write_Guided(void)
{
#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
if (control_mode != &mode_guided) {
return;
}
Expand All @@ -277,7 +277,7 @@ void Plane::Log_Write_Guided(void)
if ( is_positive(guided_state.target_alt) || is_positive(guided_state.target_airspeed_cm) ) {
Log_Write_OFG_Guided();
}
#endif // OFFBOARD_GUIDED == ENABLED
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
}

// incoming-to-vehicle mavlink COMMAND_INT can be logged
Expand Down Expand Up @@ -483,7 +483,7 @@ const struct LogStructure Plane::log_structure[] = {
{ LOG_AETR_MSG, sizeof(log_AETR),
"AETR", "Qfffffff", "TimeUS,Ail,Elev,Thr,Rudd,Flap,Steer,SS", "s-------", "F-------" , true },

#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
// @LoggerMessage: OFG
// @Description: OFfboard-Guided - an advanced version of GUIDED for companion computers that includes rate/s.
// @Field: TimeUS: Time since system startup
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -782,7 +782,7 @@ const AP_Param::Info Plane::var_info[] = {
GOBJECT(relay, "RELAY", AP_Relay),
#endif

#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
// @Group: CHUTE_
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
GOBJECT(parachute, "CHUTE_", AP_Parachute),
Expand Down Expand Up @@ -1218,11 +1218,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard
AP_GROUPINFO("RTL_CLIMB_MIN", 27, ParametersG2, rtl_climb_min, 0),

#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
// @Group: GUIDED_
// @Path: ../libraries/AC_PID/AC_PID.cpp
AP_SUBGROUPINFO(guidedHeading, "GUIDED_", 28, ParametersG2, AC_PID),
#endif // OFFBOARD_GUIDED == ENABLED
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED

// @Param: MAN_EXPO_ROLL
// @DisplayName: Manual control expo for roll
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -555,7 +555,7 @@ class ParametersG2 {
} fwd_batt_cmp;


#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
// guided yaw heading PID
AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.0};
#endif
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -553,7 +553,7 @@ class Plane : public AP_Vehicle {
float forced_throttle;
uint32_t last_forced_throttle_ms;

#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
// airspeed adjustments
float target_airspeed_cm = -1; // don't default to zero here, as zero is a valid speed.
float target_airspeed_accel;
Expand All @@ -572,7 +572,7 @@ class Plane : public AP_Vehicle {
uint32_t target_heading_time_ms;
guided_heading_type_t target_heading_type;
bool target_heading_limit;
#endif // OFFBOARD_GUIDED == ENABLED
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
} guided_state;

#if AP_LANDINGGEAR_ENABLED
Expand Down Expand Up @@ -649,7 +649,7 @@ class Plane : public AP_Vehicle {
FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)};


#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
AP_Parachute parachute;
#endif

Expand Down Expand Up @@ -1155,7 +1155,7 @@ class Plane : public AP_Vehicle {

// parachute.cpp
void parachute_check();
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
void do_parachute(const AP_Mission::Mission_Command& cmd);
void parachute_release();
bool parachute_manual_release();
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -353,7 +353,7 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break;

case AUX_FUNC::PARACHUTE_RELEASE:
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
if (ch_flag == AuxSwitchPos::HIGH) {
plane.parachute_manual_release();
}
Expand Down
18 changes: 2 additions & 16 deletions ArduPlane/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,6 @@

#include "defines.h"

// Just so that it's completely clear...
#define ENABLED 1
#define DISABLED 0

// this avoids a very common config error
#define ENABLE ENABLED
#define DISABLE DISABLED

//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// HARDWARE CONFIGURATION AND CONNECTIONS
Expand Down Expand Up @@ -213,14 +205,8 @@
# define FENCE_TRIGGERED_PIN -1
#endif

//////////////////////////////////////////////////////////////////////////////
// Parachute release
#ifndef PARACHUTE
#define PARACHUTE HAL_PARACHUTE_ENABLED
#endif

#ifndef OFFBOARD_GUIDED
#define OFFBOARD_GUIDED 1
#ifndef AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
#define AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED 1
#endif

//////////////////////////////////////////////////////////////////////////////
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
break;
}
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
parachute_release();
#endif
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
Expand Down Expand Up @@ -187,7 +187,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
case Mode::Number::GUIDED:

if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
parachute_release();
#endif
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
Expand Down Expand Up @@ -311,7 +311,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
break;

case Failsafe_Action_Parachute:
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
parachute_release();
#endif
break;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/is_flying.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ void Plane::update_is_flying_5Hz(void)
#if HAL_ADSB_ENABLED
adsb.set_is_flying(new_is_flying);
#endif
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
parachute.set_is_flying(new_is_flying);
#endif
#if AP_STATS_ENABLED
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ bool Mode::enter()
plane.guided_state.last_forced_rpy_ms.zero();
plane.guided_state.last_forced_throttle_ms = 0;

#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
plane.guided_state.target_heading = -4; // radians here are in range -3.14 to 3.14, so a default value needs to be outside that range
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
plane.guided_state.target_airspeed_cm = -1; // same as above, although an airspeed of -1 is rare on plane.
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void ModeGuided::update()
plane.nav_roll_cd = constrain_int32(plane.guided_state.forced_rpy_cd.x, -plane.roll_limit_cd, plane.roll_limit_cd);
plane.update_load_factor();

#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
// guided_state.target_heading is radians at this point between -pi and pi ( defaults to -4 )
// This function is used in Guided and AvoidADSB, check for guided
} else if ((plane.control_mode == &plane.mode_guided) && (plane.guided_state.target_heading_type != GUIDED_HEADING_NONE) ) {
Expand Down Expand Up @@ -70,7 +70,7 @@ void ModeGuided::update()
plane.nav_roll_cd = constrain_int32(desired, -bank_limit, bank_limit);
plane.update_load_factor();

#endif // OFFBOARD_GUIDED == ENABLED
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
} else {
plane.calc_nav_roll();
}
Expand Down Expand Up @@ -128,7 +128,7 @@ void ModeGuided::set_radius_and_direction(const float radius, const bool directi

void ModeGuided::update_target_altitude()
{
#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
if (((plane.guided_state.target_alt_time_ms != 0) || plane.guided_state.target_alt > -0.001 )) { // target_alt now defaults to -1, and _time_ms defaults to zero.
// offboard altitude demanded
uint32_t now = AP_HAL::millis();
Expand All @@ -148,7 +148,7 @@ void ModeGuided::update_target_altitude()
plane.guided_state.last_target_alt = temp.alt;
plane.set_target_altitude_location(temp);
} else
#endif // OFFBOARD_GUIDED == ENABLED
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
{
Mode::update_target_altitude();
}
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/navigation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ void Plane::calc_airspeed_errors()
target_airspeed_cm = ((int32_t)(aparm.airspeed_max - aparm.airspeed_min) *
get_throttle_input()) + ((int32_t)aparm.airspeed_min * 100);
}
#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
} else if (control_mode == &mode_guided && guided_state.target_airspeed_cm > 0.0) { // if offboard guided speed change cmd not set, then this section is skipped
// offboard airspeed demanded
uint32_t now = AP_HAL::millis();
Expand All @@ -203,7 +203,7 @@ void Plane::calc_airspeed_errors()
target_airspeed_cm = constrain_float(MAX(guided_state.target_airspeed_cm, target_airspeed_cm), aparm.airspeed_min *100, aparm.airspeed_max *100);
}

#endif // OFFBOARD_GUIDED == ENABLED
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED

#if HAL_SOARING_ENABLED
} else if (g2.soaring_controller.is_active() && g2.soaring_controller.get_throttle_suppressed()) {
Expand Down Expand Up @@ -256,7 +256,7 @@ void Plane::calc_airspeed_errors()
}

// when using the special GUIDED mode features for slew control, don't allow airspeed nudging as it doesn't play nicely.
#if OFFBOARD_GUIDED == ENABLED
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
if (control_mode == &mode_guided && !is_zero(guided_state.target_airspeed_cm) && (airspeed_nudge_cm != 0)) {
airspeed_nudge_cm = 0; //airspeed_nudge_cm forced to zero
}
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/parachute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,13 @@
*/
void Plane::parachute_check()
{
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
parachute.update();
parachute.check_sink_rate();
#endif
}

#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED

/*
parachute_release - trigger the release of the parachute
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ bool Plane::suppress_throttle(void)
return false;
}

#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
if (control_mode->does_auto_throttle() && parachute.release_initiated()) {
// throttle always suppressed in auto-throttle modes after parachute release initiated
throttle_suppressed = true;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ void Plane::init_ardupilot()
gcs().setup_uarts();


#if OSD_ENABLED == ENABLED
#if OSD_ENABLED
osd.init();
#endif

Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -3032,7 +3032,7 @@ def all_log_format_ids(self):
continue
if "#if AC_PRECLAND_ENABLED" in line:
continue
if "#if OFFBOARD_GUIDED == ENABLED" in line:
if "#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED" in line:
continue
if "#end" in line:
continue
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ define AP_LANDINGGEAR_ENABLED APM_BUILD_COPTER_OR_HELI

# Plane-specific defines; these defines are only used in the Plane
# directory, but are seen across the entire codebase:
define OFFBOARD_GUIDED 0
define AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED 0
define QAUTOTUNE_ENABLED 0

# Copter-specific defines; these defines are only used in the Copter
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -2573,7 +2573,7 @@ def write_all_lines(self, hwdat):
f = open(hwdat, 'w')
f.write('\n'.join(self.all_lines))
f.close()
if not self.is_periph_fw():
if not self.is_periph_fw() and not os.getenv("NO_ROMFS_HWDEF", False):
self.romfs["hwdef.dat"] = hwdat

def write_defaulting_define(self, f, name, value):
Expand Down
Loading