Copter: use HAL_PARACHUTE_ENABLED in place of PARACHUTE_ENABLED

This commit is contained in:
Peter Barker 2024-08-07 13:05:01 +10:00 committed by Andrew Tridgell
parent 2632e5b8a6
commit 42cf3aed97
9 changed files with 9 additions and 16 deletions

View File

@ -4,7 +4,6 @@
//#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support

View File

@ -521,7 +521,7 @@ private:
#endif
// Parachute release
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
AP_Parachute parachute;
#endif

View File

@ -795,7 +795,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
case MAV_CMD_NAV_VTOL_TAKEOFF:
return handle_MAV_CMD_NAV_TAKEOFF(packet);
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
case MAV_CMD_DO_PARACHUTE:
return handle_MAV_CMD_DO_PARACHUTE(packet);
#endif
@ -973,7 +973,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_comman
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
{
// configure or release parachute

View File

@ -453,7 +453,7 @@ const AP_Param::Info Copter::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),

View File

@ -312,7 +312,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
do_aux_function_change_mode(Mode::Number::FOLLOW, ch_flag);
break;
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
case AUX_FUNC::PARACHUTE_ENABLE:
// Parachute enable/disable
copter.parachute.enabled(ch_flag == AuxSwitchPos::HIGH);

View File

@ -120,12 +120,6 @@
# define AUTOTUNE_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Parachute release
#ifndef PARACHUTE
# define PARACHUTE HAL_PARACHUTE_ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Nav-Guided - allows external nav computer to control vehicle
#ifndef AC_NAV_GUIDED

View File

@ -229,7 +229,7 @@ void Copter::yaw_imbalance_check()
}
}
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
// Code to detect a crash main ArduCopter code
#define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute
@ -369,4 +369,4 @@ void Copter::parachute_manual_release()
parachute_release();
}
#endif // PARACHUTE == ENABLED
#endif // HAL_PARACHUTE_ENABLED

View File

@ -22,7 +22,7 @@ void Copter::update_land_and_crash_detectors()
update_land_detector();
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
// check parachute
parachute_check();
#endif

View File

@ -653,7 +653,7 @@ private:
void do_set_home(const AP_Mission::Mission_Command& cmd);
void do_roi(const AP_Mission::Mission_Command& cmd);
void do_mount_control(const AP_Mission::Mission_Command& cmd);
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
void do_parachute(const AP_Mission::Mission_Command& cmd);
#endif
#if AP_WINCH_ENABLED