mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_MotorsUGV: MOT_SPD_SCA_BASE param for min speed scaling
This replaces the hardcoded 1m/s start point for speed scaling with a configurable value
This commit is contained in:
parent
374c77d9c8
commit
eb519bfb79
@ -88,6 +88,14 @@ const AP_Param::GroupInfo AP_MotorsUGV::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("VEC_THR_BASE", 10, AP_MotorsUGV, _vector_throttle_base, 0.0f),
|
||||
|
||||
// @Param: SPD_SCA_BASE
|
||||
// @DisplayName: Motor speed scaling base speed
|
||||
// @Description: Speed above which steering is scaled down when using regular steering/throttle vehicles. zero to disable speed scaling
|
||||
// @Units: m/s
|
||||
// @Range: 0 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SPD_SCA_BASE", 11, AP_MotorsUGV, _speed_scale_base, 1.0f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -431,9 +439,9 @@ void AP_MotorsUGV::output_regular(bool armed, float ground_speed, float steering
|
||||
steering *= constrain_float(_vector_throttle_base / fabsf(throttle), 0.0f, 1.0f);
|
||||
}
|
||||
} else {
|
||||
// scale steering down as speed increase above 1m/s
|
||||
if (fabsf(ground_speed) > 1.0f) {
|
||||
steering *= (1.0f / fabsf(ground_speed));
|
||||
// scale steering down as speed increase above MOT_SPD_SCA_BASE (1 m/s default)
|
||||
if (is_positive(_speed_scale_base) && (fabsf(ground_speed) > _speed_scale_base)) {
|
||||
steering *= (_speed_scale_base / fabsf(ground_speed));
|
||||
} else {
|
||||
// regular steering rover at low speed so set limits to stop I-term build-up in controllers
|
||||
if (!have_skid_steering()) {
|
||||
|
@ -128,6 +128,7 @@ protected:
|
||||
AP_Int8 _throttle_max; // throttle maximum percentage
|
||||
AP_Float _thrust_curve_expo; // thrust curve exponent from -1 to +1 with 0 being linear
|
||||
AP_Float _vector_throttle_base; // throttle level above which steering is scaled down when using vector thrust. zero to disable vectored thrust
|
||||
AP_Float _speed_scale_base; // speed above which steering is scaled down when using regular steering/throttle vehicles. zero to disable speed scaling
|
||||
|
||||
// internal variables
|
||||
float _steering; // requested steering as a value from -4500 to +4500
|
||||
|
Loading…
Reference in New Issue
Block a user