Plane: remove replace PARACHUTE define with AP_PARACHUTE_ENABLED

This commit is contained in:
Peter Barker 2024-08-01 13:03:14 +10:00 committed by Peter Barker
parent ba2bec07fa
commit da562369b5
10 changed files with 14 additions and 20 deletions

View File

@ -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

View File

@ -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

View File

@ -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),

View File

@ -649,7 +649,7 @@ private:
FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)};
#if PARACHUTE == ENABLED
#if HAL_PARACHUTE_ENABLED
AP_Parachute parachute;
#endif
@ -1155,7 +1155,7 @@ private:
// 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();

View File

@ -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();
}

View File

@ -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

View File

@ -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;

View File

@ -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

View File

@ -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

View File

@ -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;