From 2247d84a6a237978b641c5593867fa2524c11b56 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Aug 2024 14:29:59 +1000 Subject: [PATCH 1/7] AP_HAL_ChibiOS: add env option to omit hwdef.dat from romfs --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index c910cc523316a..0132b844df133 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -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): From 9423f3e4c5438deac16588f7fd3a0b489600b338 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Aug 2024 13:03:14 +1000 Subject: [PATCH 2/7] Plane: remove replace PARACHUTE define with AP_PARACHUTE_ENABLED --- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/GCS_Mavlink.cpp | 4 ++-- ArduPlane/Parameters.cpp | 2 +- ArduPlane/Plane.h | 4 ++-- ArduPlane/RC_Channel.cpp | 2 +- ArduPlane/config.h | 6 ------ ArduPlane/events.cpp | 6 +++--- ArduPlane/is_flying.cpp | 2 +- ArduPlane/parachute.cpp | 4 ++-- ArduPlane/servos.cpp | 2 +- 10 files changed, 14 insertions(+), 20 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index bc6d28fbfaa8a..973478239b8ae 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -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 diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index d77210f7acf56..eaa1976f62bad 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -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 @@ -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 diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index cc6bc6e6ee626..ead102ef7a32c 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -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), diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 4a78dd32e9e01..11c151811ef06 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -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 @@ -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(); diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 9230792084590..cd1d63e04a09f 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -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(); } diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 08917cbe58486..0ba606c35781f 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -213,12 +213,6 @@ # define FENCE_TRIGGERED_PIN -1 #endif -////////////////////////////////////////////////////////////////////////////// -// Parachute release -#ifndef PARACHUTE -#define PARACHUTE HAL_PARACHUTE_ENABLED -#endif - #ifndef OFFBOARD_GUIDED #define OFFBOARD_GUIDED 1 #endif diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 12abb98e3ba5a..64127c633c181 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -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) { @@ -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) { @@ -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; diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 979a640a69ee4..7118f352fe20f 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -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 diff --git a/ArduPlane/parachute.cpp b/ArduPlane/parachute.cpp index 61cec7ae0abc4..7023d3371198c 100644 --- a/ArduPlane/parachute.cpp +++ b/ArduPlane/parachute.cpp @@ -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 diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 4f7b1c44506d6..aa2c7ce3737b7 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -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; From ea87de3a8ccd7304749a86a73f5dea1852f230dc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Aug 2024 13:07:38 +1000 Subject: [PATCH 3/7] Plane: rename OFFBOARD_GUIDED to AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED and remove comparison vs ENABLED --- ArduPlane/GCS_Mavlink.cpp | 6 +++--- ArduPlane/Log.cpp | 8 ++++---- ArduPlane/Parameters.cpp | 4 ++-- ArduPlane/Parameters.h | 2 +- ArduPlane/Plane.h | 4 ++-- ArduPlane/config.h | 4 ++-- ArduPlane/mode.cpp | 2 +- ArduPlane/mode_guided.cpp | 8 ++++---- ArduPlane/navigation.cpp | 6 +++--- 9 files changed, 22 insertions(+), 22 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index eaa1976f62bad..8ae5614669da7 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -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) { @@ -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 } diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 2fdfcd618bba1..2cafded77ff71 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -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; @@ -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; } @@ -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 @@ -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 diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index ead102ef7a32c..2c4d9cfed6c56 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -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 diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index c06fcbafc0a07..38801d99631cc 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -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 diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 11c151811ef06..709710c83a092 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -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; @@ -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 diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 0ba606c35781f..03e8b9bb6cbc3 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -213,8 +213,8 @@ # define FENCE_TRIGGERED_PIN -1 #endif -#ifndef OFFBOARD_GUIDED - #define OFFBOARD_GUIDED 1 +#ifndef AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED + #define AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index a24db831fdd73..a74d7c1a9367a 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -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. diff --git a/ArduPlane/mode_guided.cpp b/ArduPlane/mode_guided.cpp index 86a3bf60c1aee..4fef88ee3c73f 100644 --- a/ArduPlane/mode_guided.cpp +++ b/ArduPlane/mode_guided.cpp @@ -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) ) { @@ -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(); } @@ -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(); @@ -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(); } diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 6a7896587114c..e2cb3c7741884 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -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(); @@ -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()) { @@ -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 } From 1cfd429605a9086756aa1587136d78cedf34f9dc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Aug 2024 13:07:55 +1000 Subject: [PATCH 4/7] Plane: remove ENABLED/ENABLE defines --- ArduPlane/config.h | 8 -------- 1 file changed, 8 deletions(-) diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 03e8b9bb6cbc3..52a54c467339d 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -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 From 4375c9e8de49e02113f00de70328bb29dee8cefb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Aug 2024 13:13:32 +1000 Subject: [PATCH 5/7] Plane: stop using ENABLED against OSD_ENABLED it uses 1 in AP_OSD_config.h --- ArduPlane/system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index dafe5e8bd7e1c..d27491ff21aae 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -57,7 +57,7 @@ void Plane::init_ardupilot() gcs().setup_uarts(); -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED osd.init(); #endif From daad556e9f9643098f94a9bd107b76d37f89227e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 3 Aug 2024 10:33:36 +1000 Subject: [PATCH 6/7] AP_HAL_ChibiOS: rename OFFBOARD_GUIDED to AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED and remove comparison vs ENABLED --- libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc index 8047ea538c07e..91bd8acd8b000 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc @@ -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 From 1a3ba45a86c863a9d7b953952ec476844006fd10 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 3 Aug 2024 10:33:37 +1000 Subject: [PATCH 7/7] Tools: rename OFFBOARD_GUIDED to AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED and remove comparison vs ENABLED --- Tools/autotest/vehicle_test_suite.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index a596dc2a37516..f4cdceaf44412 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -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