mirror of https://github.com/ArduPilot/ardupilot
Copter: Tradheli-removed hard coding of motor interlock to channel 8
This commit is contained in:
parent
d7f90963ea
commit
07d9e8c224
|
@ -211,6 +211,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
// Ensure an Aux Channel is configured for motor interlock
|
||||||
|
if (rc().find_channel_for_option(RC_Channel::aux_func_t::MOTOR_INTERLOCK) == nullptr) {
|
||||||
|
if (display_failure) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock not configured");
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // HELI_FRAME
|
#endif // HELI_FRAME
|
||||||
|
|
||||||
// check for missing terrain data
|
// check for missing terrain data
|
||||||
|
|
|
@ -139,17 +139,17 @@ 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();
|
||||||
|
float rsc_control_deglitched = 0.0f;
|
||||||
float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)RC_Channels::rc_channel(CH_8)->get_control_in()) * 0.001f;
|
RC_Channel *rc_ptr = rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_INTERLOCK);
|
||||||
|
if (rc_ptr != nullptr) {
|
||||||
|
rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)rc_ptr->get_control_in()) * 0.001f;
|
||||||
|
}
|
||||||
switch (rsc_control_mode) {
|
switch (rsc_control_mode) {
|
||||||
case ROTOR_CONTROL_MODE_SPEED_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 > 0.01f) {
|
if (motors->get_interlock()) {
|
||||||
ap.motor_interlock_switch = true;
|
|
||||||
motors->set_desired_rotor_speed(rsc_control_deglitched);
|
motors->set_desired_rotor_speed(rsc_control_deglitched);
|
||||||
} else {
|
} else {
|
||||||
ap.motor_interlock_switch = false;
|
|
||||||
motors->set_desired_rotor_speed(0.0f);
|
motors->set_desired_rotor_speed(0.0f);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -158,11 +158,9 @@ void Copter::heli_update_rotor_speed_targets()
|
||||||
case ROTOR_CONTROL_MODE_CLOSED_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.0f) {
|
if (motors->get_interlock()) {
|
||||||
ap.motor_interlock_switch = true;
|
|
||||||
motors->set_desired_rotor_speed(motors->get_rsc_setpoint());
|
motors->set_desired_rotor_speed(motors->get_rsc_setpoint());
|
||||||
}else{
|
}else{
|
||||||
ap.motor_interlock_switch = false;
|
|
||||||
motors->set_desired_rotor_speed(0.0f);
|
motors->set_desired_rotor_speed(0.0f);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue