From 2d5d74b7a89a25faf4500d99b21c3332da98b129 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 23 Mar 2022 10:01:32 +0900 Subject: [PATCH] AP_BLHeli: add reboot required to some parameters --- libraries/AP_BLHeli/AP_BLHeli.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index dfe2ba9653..eafb6f7365 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -60,6 +60,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: Enable of BLHeli pass-thru servo protocol support to specific channels. This mask is in addition to motors enabled using SERVO_BLH_AUTO (if any) // @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 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("MASK", 1, AP_BLHeli, channel_mask, 0), #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_Rover) @@ -68,6 +69,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: If set to 1 this auto-enables BLHeli pass-thru support for all multicopter motors // @Values: 0:Disabled,1:Enabled // @User: Standard + // @RebootRequired: True AP_GROUPINFO("AUTO", 2, AP_BLHeli, channel_auto, 0), #endif @@ -106,6 +108,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: When set to a non-zero value this overrides the output type for the output channels given by SERVO_BLH_MASK. This can be used to enable DShot on outputs that are not part of the multicopter motors group. // @Values: 0:None,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("OTYPE", 7, AP_BLHeli, output_type, 0), // @Param: PORT @@ -120,6 +123,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: This allows calculation of true RPM from ESC's eRPM. The default is 14. // @Range: 1 127 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("POLES", 9, AP_BLHeli, motor_poles, 14), // @Param: 3DMASK @@ -127,6 +131,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @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 // @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 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("3DMASK", 10, AP_BLHeli, channel_reversible_mask, 0), #ifdef HAL_WITH_BIDIR_DSHOT @@ -135,6 +140,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @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. // @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 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("BDMASK", 11, AP_BLHeli, channel_bidir_dshot_mask, 0), #endif // @Param: RVMASK @@ -142,6 +148,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: Mask of channels which are reversed. This is used to configure ESCs in reversed mode // @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 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("RVMASK", 12, AP_BLHeli, channel_reversed_mask, 0), AP_GROUPEND