mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
TradHeli: integrate RotorControlMode enum
This commit is contained in:
parent
e3ff4ed9c4
commit
e92296a0b7
@ -143,7 +143,7 @@ void Copter::heli_update_rotor_speed_targets()
|
|||||||
|
|
||||||
|
|
||||||
switch (rsc_control_mode) {
|
switch (rsc_control_mode) {
|
||||||
case AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH:
|
case ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH:
|
||||||
// pass through pilot desired rotor speed if control input is higher than 10, creating a deadband at the bottom
|
// pass through pilot desired rotor speed if control input is higher than 10, creating a deadband at the bottom
|
||||||
if (rsc_control_deglitched > 10) {
|
if (rsc_control_deglitched > 10) {
|
||||||
motors.set_interlock(true);
|
motors.set_interlock(true);
|
||||||
@ -153,8 +153,9 @@ void Copter::heli_update_rotor_speed_targets()
|
|||||||
motors.set_desired_rotor_speed(0);
|
motors.set_desired_rotor_speed(0);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case AP_MOTORS_HELI_RSC_MODE_SETPOINT:
|
case ROTOR_CONTROL_MODE_SPEED_SETPOINT:
|
||||||
case AP_MOTORS_HELI_RSC_MODE_THROTTLE_CURVE:
|
case ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT:
|
||||||
|
case ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT:
|
||||||
// pass setpoint through as desired rotor speed, this is almost pointless as the Setpoint serves no function in this mode
|
// pass setpoint through as desired rotor speed, this is almost pointless as the Setpoint serves no function in this mode
|
||||||
// other than being used to create a crude estimate of rotor speed
|
// other than being used to create a crude estimate of rotor speed
|
||||||
if (rsc_control_deglitched > 0) {
|
if (rsc_control_deglitched > 0) {
|
||||||
|
Loading…
Reference in New Issue
Block a user