@ -105,7 +105,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
// @Units: PWM
// @Units: PWM
// @Increment: 1
// @Increment: 1
// @User: Standard
// @User: Standard
AP_GROUPINFO ( " TAIL_SPEED " , 10 , AP_MotorsHeli_Single , _direct_drive_tailspeed , AP_MOTORS_HELI_SINGLE_DDVPT _SPEED_DEFAULT ) ,
AP_GROUPINFO ( " TAIL_SPEED " , 10 , AP_MotorsHeli_Single , _direct_drive_tailspeed , AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT ) ,
// @Param: GYR_GAIN_ACRO
// @Param: GYR_GAIN_ACRO
// @DisplayName: External Gyro Gain for ACRO
// @DisplayName: External Gyro Gain for ACRO
@ -222,7 +222,7 @@ void AP_MotorsHeli_Single::set_desired_rotor_speed(float desired_speed)
{
{
_main_rotor . set_desired_speed ( desired_speed ) ;
_main_rotor . set_desired_speed ( desired_speed ) ;
// always send desired speed to tail rotor control, will do nothing if not DDVPT not enabled
// always send desired speed to tail rotor control, will do nothing if not DDVP not enabled
_tail_rotor . set_desired_speed ( _direct_drive_tailspeed / 1000.0f ) ;
_tail_rotor . set_desired_speed ( _direct_drive_tailspeed / 1000.0f ) ;
}
}
@ -257,11 +257,11 @@ void AP_MotorsHeli_Single::calculate_scalars()
_main_rotor . set_control_mode ( static_cast < RotorControlMode > ( _rsc_mode . get ( ) ) ) ;
_main_rotor . set_control_mode ( static_cast < RotorControlMode > ( _rsc_mode . get ( ) ) ) ;
calculate_armed_scalars ( ) ;
calculate_armed_scalars ( ) ;
// send setpoints to tail rotor controller and trigger recalculation of scalars
// send setpoints to DDVP rotor controller and trigger recalculation of scalars
if ( _tail_type = = AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH ) {
if ( _tail_type = = AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH ) {
_tail_rotor . set_control_mode ( ROTOR_CONTROL_MODE_SPEED_SETPOINT ) ;
_tail_rotor . set_control_mode ( ROTOR_CONTROL_MODE_SPEED_SETPOINT ) ;
_tail_rotor . set_ramp_time ( AP_MOTORS_HELI_SINGLE_DDVPT_RAMP_TIME ) ;
_tail_rotor . set_ramp_time ( _rsc_ramp_time ) ;
_tail_rotor . set_runup_time ( AP_MOTORS_HELI_SINGLE_DDVPT_RUNUP_TIME ) ;
_tail_rotor . set_runup_time ( _rsc_runup_time ) ;
_tail_rotor . set_critical_speed ( _rsc_critical / 1000.0f ) ;
_tail_rotor . set_critical_speed ( _rsc_critical / 1000.0f ) ;
_tail_rotor . set_idle_output ( _rsc_idle_output / 1000.0f ) ;
_tail_rotor . set_idle_output ( _rsc_idle_output / 1000.0f ) ;
} else {
} else {