mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: Tradheli to check rotor speed control input before arming
Also, force rsc_control input to 0 when disarmed. This prevents condition where AP_MotorsHeli can receive a rotor speed command greater than zero while disarmed, which was causing the ColYaw function to move the rudder servo. These two changes are somewhat tied together as it required changing the arming_check to check the RSC_Control not desired_speed from AP_MotorsHeli.
This commit is contained in:
parent
abb6eba291
commit
e3a0f1568d
@ -501,6 +501,8 @@ private:
|
|||||||
// governor. Even a single "off" frame can cause the rotor to slow dramatically and take a long time to restart.
|
// governor. Even a single "off" frame can cause the rotor to slow dramatically and take a long time to restart.
|
||||||
ModeFilterInt16_Size5 rotor_speed_deglitch_filter {4};
|
ModeFilterInt16_Size5 rotor_speed_deglitch_filter {4};
|
||||||
|
|
||||||
|
int16_t rsc_control_deglitched;
|
||||||
|
|
||||||
// Tradheli flags
|
// Tradheli flags
|
||||||
struct {
|
struct {
|
||||||
uint8_t dynamic_flight : 1; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
|
uint8_t dynamic_flight : 1; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
|
||||||
|
@ -137,24 +137,30 @@ void Copter::heli_update_rotor_speed_targets()
|
|||||||
|
|
||||||
// get rotor control method
|
// get rotor control method
|
||||||
uint8_t rsc_control_mode = motors.get_rsc_mode();
|
uint8_t rsc_control_mode = motors.get_rsc_mode();
|
||||||
int16_t rsc_control_deglitched = rotor_speed_deglitch_filter.apply(g.rc_8.control_in);
|
|
||||||
|
|
||||||
switch (rsc_control_mode) {
|
rsc_control_deglitched = rotor_speed_deglitch_filter.apply(g.rc_8.control_in);
|
||||||
case AP_MOTORS_HELI_RSC_MODE_NONE:
|
|
||||||
// even though pilot passes rotors speed directly to rotor ESC via receiver, motor lib needs to know if
|
if (motors.armed()) {
|
||||||
// rotor is spinning in case we are using direct drive tailrotor which must be spun up at same time
|
switch (rsc_control_mode) {
|
||||||
case AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH:
|
case AP_MOTORS_HELI_RSC_MODE_NONE:
|
||||||
// pass through pilot desired rotor speed
|
// even though pilot passes rotors speed directly to rotor ESC via receiver, motor lib needs to know if
|
||||||
motors.set_desired_rotor_speed(rsc_control_deglitched);
|
// rotor is spinning in case we are using direct drive tailrotor which must be spun up at same time
|
||||||
break;
|
case AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH:
|
||||||
case AP_MOTORS_HELI_RSC_MODE_SETPOINT:
|
// pass through pilot desired rotor speed
|
||||||
// pass setpoint through as desired rotor speed
|
motors.set_desired_rotor_speed(rsc_control_deglitched);
|
||||||
if (rsc_control_deglitched > 0) {
|
break;
|
||||||
motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
|
case AP_MOTORS_HELI_RSC_MODE_SETPOINT:
|
||||||
}else{
|
// pass setpoint through as desired rotor speed
|
||||||
motors.set_desired_rotor_speed(0);
|
if (rsc_control_deglitched > 0) {
|
||||||
}
|
motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
|
||||||
break;
|
}else{
|
||||||
|
motors.set_desired_rotor_speed(0);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// if disarmed, force desired_rotor_speed to Zero
|
||||||
|
motors.set_desired_rotor_speed(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// when rotor_runup_complete changes to true, log event
|
// when rotor_runup_complete changes to true, log event
|
||||||
|
@ -702,15 +702,15 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// always check if rotor is spinning on heli
|
// always check if rotor is spinning on heli
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// heli specific arming check
|
// heli specific arming check
|
||||||
if (!motors.allow_arming()){
|
if ((rsc_control_deglitched > 0) || !motors.allow_arming()){
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Rotor Control Engaged"));
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Rotor Control Engaged"));
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif // HELI_FRAME
|
#endif // HELI_FRAME
|
||||||
|
|
||||||
// succeed if arming checks are disabled
|
// succeed if arming checks are disabled
|
||||||
if (g.arming_check == ARMING_CHECK_NONE) {
|
if (g.arming_check == ARMING_CHECK_NONE) {
|
||||||
|
Loading…
Reference in New Issue
Block a user