mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_Proximity: 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
5a2a82437a
commit
adc919c7fc
@ -44,7 +44,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _YAW_CORR
|
// @Param: _YAW_CORR
|
||||||
// @DisplayName: Proximity sensor yaw correction
|
// @DisplayName: Proximity sensor yaw correction
|
||||||
// @Description: Proximity sensor yaw correction
|
// @Description: Proximity sensor yaw correction
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: -180 180
|
// @Range: -180 180
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity, _yaw_correction[0], PROXIMITY_YAW_CORRECTION_DEFAULT),
|
AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity, _yaw_correction[0], PROXIMITY_YAW_CORRECTION_DEFAULT),
|
||||||
@ -52,7 +52,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_ANG1
|
// @Param: _IGN_ANG1
|
||||||
// @DisplayName: Proximity sensor ignore angle 1
|
// @DisplayName: Proximity sensor ignore angle 1
|
||||||
// @Description: Proximity sensor ignore angle 1
|
// @Description: Proximity sensor ignore angle 1
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 360
|
// @Range: 0 360
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_ANG1", 4, AP_Proximity, _ignore_angle_deg[0], 0),
|
AP_GROUPINFO("_IGN_ANG1", 4, AP_Proximity, _ignore_angle_deg[0], 0),
|
||||||
@ -60,7 +60,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_WID1
|
// @Param: _IGN_WID1
|
||||||
// @DisplayName: Proximity sensor ignore width 1
|
// @DisplayName: Proximity sensor ignore width 1
|
||||||
// @Description: Proximity sensor ignore width 1
|
// @Description: Proximity sensor ignore width 1
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 45
|
// @Range: 0 45
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_WID1", 5, AP_Proximity, _ignore_width_deg[0], 0),
|
AP_GROUPINFO("_IGN_WID1", 5, AP_Proximity, _ignore_width_deg[0], 0),
|
||||||
@ -68,7 +68,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_ANG2
|
// @Param: _IGN_ANG2
|
||||||
// @DisplayName: Proximity sensor ignore angle 2
|
// @DisplayName: Proximity sensor ignore angle 2
|
||||||
// @Description: Proximity sensor ignore angle 2
|
// @Description: Proximity sensor ignore angle 2
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 360
|
// @Range: 0 360
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_ANG2", 6, AP_Proximity, _ignore_angle_deg[1], 0),
|
AP_GROUPINFO("_IGN_ANG2", 6, AP_Proximity, _ignore_angle_deg[1], 0),
|
||||||
@ -76,7 +76,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_WID2
|
// @Param: _IGN_WID2
|
||||||
// @DisplayName: Proximity sensor ignore width 2
|
// @DisplayName: Proximity sensor ignore width 2
|
||||||
// @Description: Proximity sensor ignore width 2
|
// @Description: Proximity sensor ignore width 2
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 45
|
// @Range: 0 45
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_WID2", 7, AP_Proximity, _ignore_width_deg[1], 0),
|
AP_GROUPINFO("_IGN_WID2", 7, AP_Proximity, _ignore_width_deg[1], 0),
|
||||||
@ -84,7 +84,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_ANG3
|
// @Param: _IGN_ANG3
|
||||||
// @DisplayName: Proximity sensor ignore angle 3
|
// @DisplayName: Proximity sensor ignore angle 3
|
||||||
// @Description: Proximity sensor ignore angle 3
|
// @Description: Proximity sensor ignore angle 3
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 360
|
// @Range: 0 360
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_ANG3", 8, AP_Proximity, _ignore_angle_deg[2], 0),
|
AP_GROUPINFO("_IGN_ANG3", 8, AP_Proximity, _ignore_angle_deg[2], 0),
|
||||||
@ -92,7 +92,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_WID3
|
// @Param: _IGN_WID3
|
||||||
// @DisplayName: Proximity sensor ignore width 3
|
// @DisplayName: Proximity sensor ignore width 3
|
||||||
// @Description: Proximity sensor ignore width 3
|
// @Description: Proximity sensor ignore width 3
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 45
|
// @Range: 0 45
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_WID3", 9, AP_Proximity, _ignore_width_deg[2], 0),
|
AP_GROUPINFO("_IGN_WID3", 9, AP_Proximity, _ignore_width_deg[2], 0),
|
||||||
@ -100,7 +100,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_ANG4
|
// @Param: _IGN_ANG4
|
||||||
// @DisplayName: Proximity sensor ignore angle 4
|
// @DisplayName: Proximity sensor ignore angle 4
|
||||||
// @Description: Proximity sensor ignore angle 4
|
// @Description: Proximity sensor ignore angle 4
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 360
|
// @Range: 0 360
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_ANG4", 10, AP_Proximity, _ignore_angle_deg[3], 0),
|
AP_GROUPINFO("_IGN_ANG4", 10, AP_Proximity, _ignore_angle_deg[3], 0),
|
||||||
@ -108,7 +108,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_WID4
|
// @Param: _IGN_WID4
|
||||||
// @DisplayName: Proximity sensor ignore width 4
|
// @DisplayName: Proximity sensor ignore width 4
|
||||||
// @Description: Proximity sensor ignore width 4
|
// @Description: Proximity sensor ignore width 4
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 45
|
// @Range: 0 45
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_WID4", 11, AP_Proximity, _ignore_width_deg[3], 0),
|
AP_GROUPINFO("_IGN_WID4", 11, AP_Proximity, _ignore_width_deg[3], 0),
|
||||||
@ -116,7 +116,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_ANG5
|
// @Param: _IGN_ANG5
|
||||||
// @DisplayName: Proximity sensor ignore angle 5
|
// @DisplayName: Proximity sensor ignore angle 5
|
||||||
// @Description: Proximity sensor ignore angle 5
|
// @Description: Proximity sensor ignore angle 5
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 360
|
// @Range: 0 360
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_ANG5", 12, AP_Proximity, _ignore_angle_deg[4], 0),
|
AP_GROUPINFO("_IGN_ANG5", 12, AP_Proximity, _ignore_angle_deg[4], 0),
|
||||||
@ -124,7 +124,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_WID5
|
// @Param: _IGN_WID5
|
||||||
// @DisplayName: Proximity sensor ignore width 5
|
// @DisplayName: Proximity sensor ignore width 5
|
||||||
// @Description: Proximity sensor ignore width 5
|
// @Description: Proximity sensor ignore width 5
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 45
|
// @Range: 0 45
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_WID5", 13, AP_Proximity, _ignore_width_deg[4], 0),
|
AP_GROUPINFO("_IGN_WID5", 13, AP_Proximity, _ignore_width_deg[4], 0),
|
||||||
@ -132,7 +132,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_ANG6
|
// @Param: _IGN_ANG6
|
||||||
// @DisplayName: Proximity sensor ignore angle 6
|
// @DisplayName: Proximity sensor ignore angle 6
|
||||||
// @Description: Proximity sensor ignore angle 6
|
// @Description: Proximity sensor ignore angle 6
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 360
|
// @Range: 0 360
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_ANG6", 14, AP_Proximity, _ignore_angle_deg[5], 0),
|
AP_GROUPINFO("_IGN_ANG6", 14, AP_Proximity, _ignore_angle_deg[5], 0),
|
||||||
@ -140,7 +140,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: _IGN_WID6
|
// @Param: _IGN_WID6
|
||||||
// @DisplayName: Proximity sensor ignore width 6
|
// @DisplayName: Proximity sensor ignore width 6
|
||||||
// @Description: Proximity sensor ignore width 6
|
// @Description: Proximity sensor ignore width 6
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: 0 45
|
// @Range: 0 45
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_IGN_WID6", 15, AP_Proximity, _ignore_width_deg[5], 0),
|
AP_GROUPINFO("_IGN_WID6", 15, AP_Proximity, _ignore_width_deg[5], 0),
|
||||||
@ -164,7 +164,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
|||||||
// @Param: 2_YAW_CORR
|
// @Param: 2_YAW_CORR
|
||||||
// @DisplayName: Second Proximity sensor yaw correction
|
// @DisplayName: Second Proximity sensor yaw correction
|
||||||
// @Description: Second Proximity sensor yaw correction
|
// @Description: Second Proximity sensor yaw correction
|
||||||
// @Units: degrees
|
// @Units: deg
|
||||||
// @Range: -180 180
|
// @Range: -180 180
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("2_YAW_CORR", 18, AP_Proximity, _yaw_correction[1], PROXIMITY_YAW_CORRECTION_DEFAULT),
|
AP_GROUPINFO("2_YAW_CORR", 18, AP_Proximity, _yaw_correction[1], PROXIMITY_YAW_CORRECTION_DEFAULT),
|
||||||
|
Loading…
Reference in New Issue
Block a user