mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Motors: 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
This commit is contained in:
parent
44eca002f0
commit
9d9ebc91cd
@ -85,7 +85,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
// @DisplayName: Landing Collective Minimum
|
||||
// @Description: Minimum collective position while landed or landing
|
||||
// @Range: 0 500
|
||||
// @Units: pwm
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("LAND_COL_MIN", 9, AP_MotorsHeli, _land_collective_min, AP_MOTORS_HELI_LAND_COLLECTIVE_MIN),
|
||||
@ -94,7 +94,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
// @DisplayName: RSC Ramp Time
|
||||
// @Description: Time in seconds for the output to the main rotor's ESC to reach full speed
|
||||
// @Range: 0 60
|
||||
// @Units: Seconds
|
||||
// @Units: s
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RSC_RAMP_TIME", 10, AP_MotorsHeli, _rsc_ramp_time, AP_MOTORS_HELI_RSC_RAMP_TIME),
|
||||
|
||||
@ -102,7 +102,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
// @DisplayName: RSC Runup Time
|
||||
// @Description: Time in seconds for the main rotor to reach full speed. Must be longer than RSC_RAMP_TIME
|
||||
// @Range: 0 60
|
||||
// @Units: Seconds
|
||||
// @Units: s
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RSC_RUNUP_TIME", 11, AP_MotorsHeli, _rsc_runup_time, AP_MOTORS_HELI_RSC_RUNUP_TIME),
|
||||
|
||||
@ -142,7 +142,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
// @DisplayName: Cyclic Pitch Angle Max
|
||||
// @Description: Maximum pitch angle of the swash plate
|
||||
// @Range: 0 18000
|
||||
// @Units: Centi-Degrees
|
||||
// @Units: cdeg
|
||||
// @Increment: 100
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CYC_MAX", 16, AP_MotorsHeli, _cyclic_max, AP_MOTORS_HELI_SWASH_CYCLIC_MAX),
|
||||
|
@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Servo 1 Position
|
||||
// @Description: Angular location of swash servo #1
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli_Dual, _servo1_pos, AP_MOTORS_HELI_DUAL_SERVO1_POS),
|
||||
@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Servo 2 Position
|
||||
// @Description: Angular location of swash servo #2
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli_Dual, _servo2_pos, AP_MOTORS_HELI_DUAL_SERVO2_POS),
|
||||
@ -45,7 +45,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Servo 3 Position
|
||||
// @Description: Angular location of swash servo #3
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV3_POS", 3, AP_MotorsHeli_Dual, _servo3_pos, AP_MOTORS_HELI_DUAL_SERVO3_POS),
|
||||
@ -54,7 +54,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Servo 4 Position
|
||||
// @Description: Angular location of swash servo #4
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV4_POS", 4, AP_MotorsHeli_Dual, _servo4_pos, AP_MOTORS_HELI_DUAL_SERVO4_POS),
|
||||
@ -63,7 +63,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Servo 5 Position
|
||||
// @Description: Angular location of swash servo #5
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV5_POS", 5, AP_MotorsHeli_Dual, _servo5_pos, AP_MOTORS_HELI_DUAL_SERVO5_POS),
|
||||
@ -72,7 +72,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Servo 6 Position
|
||||
// @Description: Angular location of swash servo #6
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV6_POS", 6, AP_MotorsHeli_Dual, _servo6_pos, AP_MOTORS_HELI_DUAL_SERVO6_POS),
|
||||
@ -81,7 +81,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Swashplate 1 Phase Angle Compensation
|
||||
// @Description: Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
|
||||
// @Range: -90 90
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("PHANG1", 7, AP_MotorsHeli_Dual, _swash1_phase_angle, 0),
|
||||
@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
|
||||
// @DisplayName: Swashplate 2 Phase Angle Compensation
|
||||
// @Description: Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
|
||||
// @Range: -90 90
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("PHANG2", 8, AP_MotorsHeli_Dual, _swash2_phase_angle, 0),
|
||||
|
@ -28,7 +28,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
// @DisplayName: Servo 1 Position
|
||||
// @Description: Angular location of swash servo #1
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli_Single, _servo1_pos, AP_MOTORS_HELI_SINGLE_SERVO1_POS),
|
||||
@ -37,7 +37,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
// @DisplayName: Servo 2 Position
|
||||
// @Description: Angular location of swash servo #2
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli_Single, _servo2_pos, AP_MOTORS_HELI_SINGLE_SERVO2_POS),
|
||||
@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
// @DisplayName: Servo 3 Position
|
||||
// @Description: Angular location of swash servo #3
|
||||
// @Range: -180 180
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Standard
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("SV3_POS", 3, AP_MotorsHeli_Single, _servo3_pos, AP_MOTORS_HELI_SINGLE_SERVO3_POS),
|
||||
@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
// @DisplayName: Swashplate Phase Angle Compensation
|
||||
// @Description: Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
|
||||
// @Range: -90 90
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("PHANG", 7, AP_MotorsHeli_Single, _phase_angle, 0),
|
||||
|
@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @DisplayName: Matrix Yaw Min
|
||||
// @Description: Yaw control is given at least this pwm range
|
||||
// @Range: 0 500
|
||||
// @Units: pwm
|
||||
// @Units: PWM
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("YAW_HEADROOM", 6, AP_MotorsMulticopter, _yaw_headroom, AP_MOTORS_YAW_HEADROOM_DEFAULT),
|
||||
|
||||
@ -58,7 +58,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @DisplayName: Battery voltage compensation maximum voltage
|
||||
// @Description: Battery voltage compensation maximum voltage (voltage above this will have no additional scaling effect on thrust). Recommend 4.4 * cell count, 0 = Disabled
|
||||
// @Range: 6 35
|
||||
// @Units: Volts
|
||||
// @Units: V
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BAT_VOLT_MAX", 10, AP_MotorsMulticopter, _batt_voltage_max, AP_MOTORS_BAT_VOLT_MAX_DEFAULT),
|
||||
|
||||
@ -66,7 +66,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @DisplayName: Battery voltage compensation minimum voltage
|
||||
// @Description: Battery voltage compensation minimum voltage (voltage below this will have no additional scaling effect on thrust). Recommend 3.5 * cell count, 0 = Disabled
|
||||
// @Range: 6 35
|
||||
// @Units: Volts
|
||||
// @Units: V
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BAT_VOLT_MIN", 11, AP_MotorsMulticopter, _batt_voltage_min, AP_MOTORS_BAT_VOLT_MIN_DEFAULT),
|
||||
|
||||
@ -74,7 +74,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @DisplayName: Motor Current Max
|
||||
// @Description: Maximum current over which maximum throttle is limited (0 = Disabled)
|
||||
// @Range: 0 200
|
||||
// @Units: Amps
|
||||
// @Units: A
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BAT_CURR_MAX", 12, AP_MotorsMulticopter, _batt_current_max, AP_MOTORS_BAT_CURR_MAX_DEFAULT),
|
||||
|
||||
@ -91,6 +91,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @Param: PWM_MIN
|
||||
// @DisplayName: PWM output miniumum
|
||||
// @Description: This sets the min PWM output value that will ever be output to the motors, 0 = use input RC3_MIN
|
||||
// @Units: PWM
|
||||
// @Range: 0 2000
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_MIN", 16, AP_MotorsMulticopter, _pwm_min, 0),
|
||||
@ -98,6 +99,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @Param: PWM_MAX
|
||||
// @DisplayName: PWM output maximum
|
||||
// @Description: This sets the max PWM value that will ever be output to the motors, 0 = use input RC3_MAX
|
||||
// @Units: PWM
|
||||
// @Range: 0 2000
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_MAX", 17, AP_MotorsMulticopter, _pwm_max, 0),
|
||||
@ -120,7 +122,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @DisplayName: Motor Current Max Time Constant
|
||||
// @Description: Time constant used to limit the maximum current
|
||||
// @Range: 0 10
|
||||
// @Units: Seconds
|
||||
// @Units: s
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BAT_CURR_TC", 20, AP_MotorsMulticopter, _batt_current_time_constant, AP_MOTORS_BAT_CURR_TC_DEFAULT),
|
||||
|
||||
@ -149,7 +151,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @DisplayName: Yaw Servo Max Lean Angle
|
||||
// @Description: Yaw servo's maximum lean angle
|
||||
// @Range: 5 80
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FRAME("YAW_SV_ANGLE", 35, AP_MotorsMulticopter, _yaw_servo_angle_max_deg, 30, AP_PARAM_FRAME_TRICOPTER),
|
||||
@ -158,7 +160,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||
// @DisplayName: Spool up time
|
||||
// @Description: Time in seconds to spool up the motors from zero to min throttle.
|
||||
// @Range: 0 2
|
||||
// @Units: Seconds
|
||||
// @Units: s
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SPOOL_TIME", 36, AP_MotorsMulticopter, _spool_up_time, AP_MOTORS_SPOOL_UP_TIME_DEFAULT),
|
||||
|
Loading…
Reference in New Issue
Block a user