|
|
|
@ -241,7 +241,7 @@ void AP_MotorsHeli_Single::calculate_scalars()
@@ -241,7 +241,7 @@ void AP_MotorsHeli_Single::calculate_scalars()
|
|
|
|
|
calculate_roll_pitch_collective_factors(); |
|
|
|
|
|
|
|
|
|
// send setpoints to main rotor controller and trigger recalculation of scalars
|
|
|
|
|
_main_rotor.set_control_mode(_rsc_mode);
|
|
|
|
|
_main_rotor.set_control_mode(static_cast<RotorControlMode>(_rsc_mode.get())); |
|
|
|
|
_main_rotor.set_ramp_time(_rsc_ramp_time); |
|
|
|
|
_main_rotor.set_runup_time(_rsc_runup_time); |
|
|
|
|
_main_rotor.set_critical_speed(_rsc_critical); |
|
|
|
@ -251,13 +251,13 @@ void AP_MotorsHeli_Single::calculate_scalars()
@@ -251,13 +251,13 @@ void AP_MotorsHeli_Single::calculate_scalars()
|
|
|
|
|
|
|
|
|
|
// send setpoints to tail rotor controller and trigger recalculation of scalars
|
|
|
|
|
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) { |
|
|
|
|
_tail_rotor.set_control_mode(AP_MOTORS_HELI_RSC_MODE_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_runup_time(AP_MOTORS_HELI_SINGLE_DDVPT_RUNUP_TIME); |
|
|
|
|
_tail_rotor.set_critical_speed(_rsc_critical); |
|
|
|
|
_tail_rotor.set_idle_output(_rsc_idle_output); |
|
|
|
|
} else { |
|
|
|
|
_tail_rotor.set_control_mode(AP_MOTORS_HELI_RSC_MODE_DISABLED); |
|
|
|
|
_tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_DISABLED); |
|
|
|
|
_tail_rotor.set_ramp_time(0); |
|
|
|
|
_tail_rotor.set_runup_time(0); |
|
|
|
|
_tail_rotor.set_critical_speed(0); |
|
|
|
@ -314,7 +314,7 @@ uint16_t AP_MotorsHeli_Single::get_motor_mask()
@@ -314,7 +314,7 @@ uint16_t AP_MotorsHeli_Single::get_motor_mask()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// update_motor_controls - sends commands to motor controllers
|
|
|
|
|
void AP_MotorsHeli_Single::update_motor_control(uint8_t state) |
|
|
|
|
void AP_MotorsHeli_Single::update_motor_control(RotorControlState state) |
|
|
|
|
{ |
|
|
|
|
// Send state update to motors
|
|
|
|
|
_tail_rotor.output(state); |
|
|
|
@ -470,4 +470,4 @@ void AP_MotorsHeli_Single::write_aux(int16_t servo_out)
@@ -470,4 +470,4 @@ void AP_MotorsHeli_Single::write_aux(int16_t servo_out)
|
|
|
|
|
_servo_aux.servo_out = servo_out; |
|
|
|
|
_servo_aux.calc_pwm(); |
|
|
|
|
hal.rcout->write(AP_MOTORS_HELI_SINGLE_AUX, _servo_aux.radio_out); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|