mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Remove PILOT_THR_BEHAVIOR parameter and disable auto_disarm_check()
This commit is contained in:
parent
cfc94b65f5
commit
d11b07bd4f
@ -84,14 +84,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Increment: .5
|
||||
GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),
|
||||
|
||||
// @Param: PILOT_THR_BHV
|
||||
// @DisplayName: Throttle stick behavior
|
||||
// @Description: Bitmask containing various throttle stick options. Add up the values for options that you want.
|
||||
// @User: Standard
|
||||
// @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection
|
||||
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
|
||||
GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),
|
||||
|
||||
// @Group: SERIAL
|
||||
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
|
||||
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
|
||||
|
@ -240,9 +240,6 @@ public:
|
||||
k_param_autotune_axis_bitmask, // Disabled
|
||||
k_param_autotune_aggressiveness, // Disabled
|
||||
k_param_autotune_min_d, // Disabled
|
||||
|
||||
|
||||
k_param_throttle_behavior, // ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Remove
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
@ -257,7 +254,6 @@ public:
|
||||
#endif
|
||||
|
||||
AP_Float throttle_filt;
|
||||
AP_Int16 throttle_behavior;
|
||||
|
||||
AP_Float rangefinder_gain;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user