|
|
|
@ -132,6 +132,27 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
@@ -132,6 +132,27 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
|
|
|
|
// @Path: ../RC_Channel/RC_Channel.cpp
|
|
|
|
|
AP_SUBGROUPINFO(_yaw_servo, "SV4_", 15, AP_MotorsHeli_Single, RC_Channel), |
|
|
|
|
|
|
|
|
|
// @Param: RSC_PWM_MIN
|
|
|
|
|
// @DisplayName: RSC PWM output miniumum
|
|
|
|
|
// @Description: This sets the PWM output on RSC channel for maximum rotor speed
|
|
|
|
|
// @Range: 0 2000
|
|
|
|
|
// @User: Standard
|
|
|
|
|
AP_GROUPINFO("RSC_PWM_MIN", 16, AP_MotorsHeli_Single, _main_rotor._pwm_min, 1000), |
|
|
|
|
|
|
|
|
|
// @Param: RSC_PWM_MAX
|
|
|
|
|
// @DisplayName: RSC PWM output maxiumum
|
|
|
|
|
// @Description: This sets the PWM output on RSC channel for miniumum rotor speed
|
|
|
|
|
// @Range: 0 2000
|
|
|
|
|
// @User: Standard
|
|
|
|
|
AP_GROUPINFO("RSC_PWM_MAX", 17, AP_MotorsHeli_Single, _main_rotor._pwm_max, 2000), |
|
|
|
|
|
|
|
|
|
// @Param: RSC_PWM_REV
|
|
|
|
|
// @DisplayName: RSC PWM reversal
|
|
|
|
|
// @Description: This controls reversal of the RSC channel output
|
|
|
|
|
// @Values: -1:Reversed,1:Normal
|
|
|
|
|
// @User: Standard
|
|
|
|
|
AP_GROUPINFO("RSC_PWM_REV", 18, AP_MotorsHeli_Single, _main_rotor._pwm_rev, 1), |
|
|
|
|
|
|
|
|
|
// parameters up to and including 29 are reserved for tradheli
|
|
|
|
|
|
|
|
|
|
AP_GROUPEND |
|
|
|
|