mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 09:24:01 -04:00
Sub: Add RC_SLEW_RATE parameter
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com> Co-authored-by: Jacob Walser <jwalser90@gmail.com>
This commit is contained in:
parent
ee36509cb8
commit
f04a861c58
@ -398,6 +398,15 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @User: Advanced
|
||||
GSCALAR(rc_speed, "RC_SPEED", RC_SPEED_DEFAULT),
|
||||
|
||||
// @Param: MANUAL_SLEW_RATE
|
||||
// @DisplayName: RC Channel Update Slew Rate
|
||||
// @Description: This is slew rate in %/s that will be used in manual mode to avoid large step outputs on the motors. Set to zero to disable.
|
||||
// @Units: %/s
|
||||
// @Range: 0 500
|
||||
// @Increment: 10
|
||||
// @User: Advanced
|
||||
GSCALAR(manual_slew_rate, "MANUAL_SLEW_RATE", 100),
|
||||
|
||||
// @Param: ACRO_RP_P
|
||||
// @DisplayName: Acro Roll and Pitch P gain
|
||||
// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
|
||||
|
@ -185,6 +185,7 @@ public:
|
||||
k_param_compass_enabled,
|
||||
k_param_surface_depth,
|
||||
k_param_rc_speed, // Main output pwm frequency
|
||||
k_param_manual_slew_rate, // manual mode motors mixer slew rate
|
||||
k_param_gcs_pid_mask = 178,
|
||||
k_param_throttle_filt,
|
||||
k_param_throttle_deadzone, // Used in auto-throttle modes
|
||||
@ -267,6 +268,7 @@ public:
|
||||
AP_Int8 terrain_follow;
|
||||
|
||||
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
|
||||
AP_Int16 manual_slew_rate;
|
||||
|
||||
AP_Float gain_default;
|
||||
AP_Float maxGain;
|
||||
|
Loading…
Reference in New Issue
Block a user