Browse Source

APM_Control: Use SI units conventions in parameter units

Follow the rules from:
http://physics.nist.gov/cuu/Units/units.html
http://physics.nist.gov/cuu/Units/outside.html
and
http://physics.nist.gov/cuu/Units/checklist.html
one further constrain is that only printable (7bit) ASCII characters are allowed
master
Dr.-Ing. Amilcar Do Carmo Lucas 8 years ago committed by Andrew Tridgell
parent
commit
0f5d1ae2dd
  1. 6
      libraries/APM_Control/AP_PitchController.cpp
  2. 4
      libraries/APM_Control/AP_RollController.cpp
  3. 11
      libraries/APM_Control/AP_SteerController.cpp

6
libraries/APM_Control/AP_PitchController.cpp

@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
// @DisplayName: Pitch Time Constant // @DisplayName: Pitch Time Constant
// @Description: This controls the time constant in seconds from demanded to achieved pitch angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve. // @Description: This controls the time constant in seconds from demanded to achieved pitch angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve.
// @Range: 0.4 1.0 // @Range: 0.4 1.0
// @Units: seconds // @Units: s
// @Increment: 0.1 // @Increment: 0.1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("TCONST", 0, AP_PitchController, gains.tau, 0.5f), AP_GROUPINFO("TCONST", 0, AP_PitchController, gains.tau, 0.5f),
@ -60,7 +60,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
// @DisplayName: Pitch up max rate // @DisplayName: Pitch up max rate
// @Description: This sets the maximum nose up pitch rate that the controller will demand (degrees/sec). Setting it to zero disables the limit. // @Description: This sets the maximum nose up pitch rate that the controller will demand (degrees/sec). Setting it to zero disables the limit.
// @Range: 0 100 // @Range: 0 100
// @Units: degrees/second // @Units: deg/s
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("RMAX_UP", 4, AP_PitchController, gains.rmax, 0.0f), AP_GROUPINFO("RMAX_UP", 4, AP_PitchController, gains.rmax, 0.0f),
@ -69,7 +69,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
// @DisplayName: Pitch down max rate // @DisplayName: Pitch down max rate
// @Description: This sets the maximum nose down pitch rate that the controller will demand (degrees/sec). Setting it to zero disables the limit. // @Description: This sets the maximum nose down pitch rate that the controller will demand (degrees/sec). Setting it to zero disables the limit.
// @Range: 0 100 // @Range: 0 100
// @Units: degrees/second // @Units: deg/s
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("RMAX_DN", 5, AP_PitchController, _max_rate_neg, 0.0f), AP_GROUPINFO("RMAX_DN", 5, AP_PitchController, _max_rate_neg, 0.0f),

4
libraries/APM_Control/AP_RollController.cpp

@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
// @DisplayName: Roll Time Constant // @DisplayName: Roll Time Constant
// @Description: This controls the time constant in seconds from demanded to achieved bank angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve. // @Description: This controls the time constant in seconds from demanded to achieved bank angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve.
// @Range: 0.4 1.0 // @Range: 0.4 1.0
// @Units: seconds // @Units: s
// @Increment: 0.1 // @Increment: 0.1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("TCONST", 0, AP_RollController, gains.tau, 0.5f), AP_GROUPINFO("TCONST", 0, AP_RollController, gains.tau, 0.5f),
@ -60,7 +60,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
// @DisplayName: Maximum Roll Rate // @DisplayName: Maximum Roll Rate
// @Description: This sets the maximum roll rate that the controller will demand (degrees/sec). Setting it to zero disables the limit. If this value is set too low, then the roll can't keep up with the navigation demands and the plane will start weaving. If it is set too high (or disabled by setting to zero) then ailerons will get large inputs at the start of turns. A limit of 60 degrees/sec is a good default. // @Description: This sets the maximum roll rate that the controller will demand (degrees/sec). Setting it to zero disables the limit. If this value is set too low, then the roll can't keep up with the navigation demands and the plane will start weaving. If it is set too high (or disabled by setting to zero) then ailerons will get large inputs at the start of turns. A limit of 60 degrees/sec is a good default.
// @Range: 0 180 // @Range: 0 180
// @Units: degrees/second // @Units: deg/s
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("RMAX", 4, AP_RollController, gains.rmax, 0), AP_GROUPINFO("RMAX", 4, AP_RollController, gains.rmax, 0),

11
libraries/APM_Control/AP_SteerController.cpp

@ -28,7 +28,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] = {
// @DisplayName: Steering Time Constant // @DisplayName: Steering Time Constant
// @Description: This controls the time constant in seconds from demanded to achieved steering angle. A value of 0.75 is a good default and will work with nearly all rovers. Ground steering in aircraft needs a bit smaller time constant, and a value of 0.5 is recommended for best ground handling in fixed wing aircraft. A value of 0.75 means that the controller will try to correct any deviation between the desired and actual steering angle in 0.75 seconds. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the vehicle can achieve. // @Description: This controls the time constant in seconds from demanded to achieved steering angle. A value of 0.75 is a good default and will work with nearly all rovers. Ground steering in aircraft needs a bit smaller time constant, and a value of 0.5 is recommended for best ground handling in fixed wing aircraft. A value of 0.75 means that the controller will try to correct any deviation between the desired and actual steering angle in 0.75 seconds. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the vehicle can achieve.
// @Range: 0.4 1.0 // @Range: 0.4 1.0
// @Units: seconds // @Units: s
// @Increment: 0.1 // @Increment: 0.1
// @User: Advanced // @User: Advanced
AP_GROUPINFO("TCONST", 0, AP_SteerController, _tau, 0.75f), AP_GROUPINFO("TCONST", 0, AP_SteerController, _tau, 0.75f),
@ -62,6 +62,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] = {
// @Description: This limits the number of degrees of steering in centi-degrees over which the integrator will operate. At the default setting of 1500 centi-degrees, the integrator will be limited to +- 15 degrees of servo travel. The maximum servo deflection is +- 45 centi-degrees, so the default value represents a 1/3rd of the total control throw which is adequate unless the vehicle is severely out of trim. // @Description: This limits the number of degrees of steering in centi-degrees over which the integrator will operate. At the default setting of 1500 centi-degrees, the integrator will be limited to +- 15 degrees of servo travel. The maximum servo deflection is +- 45 centi-degrees, so the default value represents a 1/3rd of the total control throw which is adequate unless the vehicle is severely out of trim.
// @Range: 0 4500 // @Range: 0 4500
// @Increment: 1 // @Increment: 1
// @Units: cdeg
// @User: Advanced // @User: Advanced
AP_GROUPINFO("IMAX", 5, AP_SteerController, _imax, 1500), AP_GROUPINFO("IMAX", 5, AP_SteerController, _imax, 1500),
@ -70,7 +71,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] = {
// @Description: This is the minimum assumed ground speed in meters/second for steering. Having a minimum speed prevents oscillations when the vehicle first starts moving. The vehicle can still drive slower than this limit, but the steering calculations will be done based on this minimum speed. // @Description: This is the minimum assumed ground speed in meters/second for steering. Having a minimum speed prevents oscillations when the vehicle first starts moving. The vehicle can still drive slower than this limit, but the steering calculations will be done based on this minimum speed.
// @Range: 0 5 // @Range: 0 5
// @Increment: 0.1 // @Increment: 0.1
// @Units: m/s // @Units: m/s
// @User: User // @User: User
AP_GROUPINFO("MINSPD", 6, AP_SteerController, _minspeed, 1.0f), AP_GROUPINFO("MINSPD", 6, AP_SteerController, _minspeed, 1.0f),
@ -89,7 +90,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] = {
// @Description: Speed after that the maximum degree of steering will start to derate. Set this speed to a maximum speed that a plane can do controlled turn at maximum angle of steering wheel without rolling to wing. If 0 then no derating is used. // @Description: Speed after that the maximum degree of steering will start to derate. Set this speed to a maximum speed that a plane can do controlled turn at maximum angle of steering wheel without rolling to wing. If 0 then no derating is used.
// @Range: 0.0 30.0 // @Range: 0.0 30.0
// @Increment: 0.1 // @Increment: 0.1
// @Units: m/s // @Units: m/s
// @User: Advanced // @User: Advanced
AP_GROUPINFO("DRTSPD", 8, AP_SteerController, _deratespeed, 0), AP_GROUPINFO("DRTSPD", 8, AP_SteerController, _deratespeed, 0),
@ -98,7 +99,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] = {
// @Description: Degrees of steering wheel to derate at each additional m/s of speed above "Derating speed". Should be set so that at higher speeds the plane does not roll to the wing in turns. // @Description: Degrees of steering wheel to derate at each additional m/s of speed above "Derating speed". Should be set so that at higher speeds the plane does not roll to the wing in turns.
// @Range: 0.0 50.0 // @Range: 0.0 50.0
// @Increment: 0.1 // @Increment: 0.1
// @Units: degree/(m/s) // @Units: deg/m/s
// @User: Advanced // @User: Advanced
AP_GROUPINFO("DRTFCT", 9, AP_SteerController, _deratefactor, 10), AP_GROUPINFO("DRTFCT", 9, AP_SteerController, _deratefactor, 10),
@ -107,7 +108,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] = {
// @Description: The angle that limits smallest angle of steering wheel at maximum speed. Even if it should derate below, it will stop derating at this angle. // @Description: The angle that limits smallest angle of steering wheel at maximum speed. Even if it should derate below, it will stop derating at this angle.
// @Range: 0.0 4500.0 // @Range: 0.0 4500.0
// @Increment: 0.1 // @Increment: 0.1
// @Units: Centidegrees // @Units: cdeg
// @User: Advanced // @User: Advanced
AP_GROUPINFO("DRTMIN", 10, AP_SteerController, _mindegree, 4500), AP_GROUPINFO("DRTMIN", 10, AP_SteerController, _mindegree, 4500),

Loading…
Cancel
Save