AP_BLHeli:expand metadata of 3d and Reverse masks

This commit is contained in:
Henry Wurzburg 2024-05-31 21:21:05 -05:00 committed by Andrew Tridgell
parent 887e4713e6
commit 3b86c0527f
1 changed files with 3 additions and 3 deletions

View File

@ -128,7 +128,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
// @Param: 3DMASK
// @DisplayName: BLHeli bitmask of 3D channels
// @Description: Mask of channels which are dynamically reversible. This is used to configure ESCs in '3D' mode, allowing for the motor to spin in either direction
// @Description: Mask of channels which are dynamically reversible. This is used to configure ESCs in '3D' mode, allowing for the motor to spin in either direction. Do not use for channels selected with SERVO_BLH_RVMASK.
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32
// @User: Advanced
// @RebootRequired: True
@ -137,7 +137,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
#if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT
// @Param: BDMASK
// @DisplayName: BLHeli bitmask of bi-directional dshot channels
// @Description: Mask of channels which support bi-directional dshot. This is used for ESCs which have firmware that supports bi-directional dshot allowing fast rpm telemetry values to be returned for the harmonic notch.
// @Description: Mask of channels which support bi-directional dshot telemetry. This is used for ESCs which have firmware that supports bi-directional dshot allowing fast rpm telemetry values to be returned for the harmonic notch.
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32
// @User: Advanced
// @RebootRequired: True
@ -145,7 +145,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
#endif
// @Param: RVMASK
// @DisplayName: BLHeli bitmask of reversed channels
// @Description: Mask of channels which are reversed. This is used to configure ESCs in reversed mode
// @Description: Mask of channels which are reversed. This is used to configure ESCs to reverse motor direction for unidirectional rotation.Do not use for channels selected with SERVO_BLH_RVMASK.Do not use for channels selected with SERVO_BLH_3DMASK.
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32
// @User: Advanced
// @RebootRequired: True