mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AR_AttitudeControl: parameter desc range increase
new steering controller can use higher FF and zero P
This commit is contained in:
parent
e2824be250
commit
5e90cdbf59
@ -24,7 +24,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Param: _STR_RAT_P
|
// @Param: _STR_RAT_P
|
||||||
// @DisplayName: Steering control rate P gain
|
// @DisplayName: Steering control rate P gain
|
||||||
// @Description: Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
|
// @Description: Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
|
||||||
// @Range: 0.100 2.000
|
// @Range: 0.000 2.000
|
||||||
// @Increment: 0.01
|
// @Increment: 0.01
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
||||||
@ -52,7 +52,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Param: _STR_RAT_FF
|
// @Param: _STR_RAT_FF
|
||||||
// @DisplayName: Steering control feed forward
|
// @DisplayName: Steering control feed forward
|
||||||
// @Description: Steering control feed forward
|
// @Description: Steering control feed forward
|
||||||
// @Range: 0 0.5
|
// @Range: 0.000 3.000
|
||||||
// @Increment: 0.001
|
// @Increment: 0.001
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
||||||
@ -95,7 +95,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Param: _SPEED_FF
|
// @Param: _SPEED_FF
|
||||||
// @DisplayName: Speed control feed forward
|
// @DisplayName: Speed control feed forward
|
||||||
// @Description: Speed control feed forward
|
// @Description: Speed control feed forward
|
||||||
// @Range: 0 0.5
|
// @Range: 0.000 0.500
|
||||||
// @Increment: 0.001
|
// @Increment: 0.001
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
||||||
@ -111,7 +111,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Param: _ACCEL_MAX
|
// @Param: _ACCEL_MAX
|
||||||
// @DisplayName: Speed control acceleration (and deceleration) maximum in m/s/s
|
// @DisplayName: Speed control acceleration (and deceleration) maximum in m/s/s
|
||||||
// @Description: Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
|
// @Description: Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
|
||||||
// @Range: 0 10
|
// @Range: 0.0 10.0
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
// @Units: m/s/s
|
// @Units: m/s/s
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
@ -127,7 +127,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
|||||||
// @Param: _STOP_SPEED
|
// @Param: _STOP_SPEED
|
||||||
// @DisplayName: Speed control stop speed
|
// @DisplayName: Speed control stop speed
|
||||||
// @Description: Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
|
// @Description: Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
|
||||||
// @Range: 0 0.5
|
// @Range: 0.00 0.50
|
||||||
// @Increment: 0.01
|
// @Increment: 0.01
|
||||||
// @Units: m/s
|
// @Units: m/s
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
Loading…
Reference in New Issue
Block a user