mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Copter: Tradheli gets support for spool logic
This commit is contained in:
parent
12f4d8518e
commit
ca565675f2
@ -375,12 +375,12 @@ bool Copter::Mode::_TakeOff::triggered(const float target_climb_rate) const
|
||||
|
||||
void Copter::Mode::zero_throttle_and_relax_ac()
|
||||
{
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Helicopters always stabilize roll/pitch/yaw
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
|
||||
attitude_control->set_throttle_out(0.0f, false, copter.g.throttle_filt);
|
||||
#else
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control->set_throttle_out_unstabilized(0.0f, true, copter.g.throttle_filt);
|
||||
#endif
|
||||
|
@ -45,6 +45,8 @@ void Copter::ModeAcro_Heli::run()
|
||||
set_land_complete(false);
|
||||
}
|
||||
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
if (!motors->has_flybar()){
|
||||
// convert the input to the desired body frame rate
|
||||
get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);
|
||||
|
@ -103,19 +103,22 @@ void Copter::ModeAltHold::run()
|
||||
break;
|
||||
|
||||
case AltHold_Landed:
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters do not spool down when landed. Only when commanded to go to ground idle by pilot.
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
if (motors->init_targets_on_arming()) {
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
}
|
||||
#else
|
||||
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
|
||||
if (target_climb_rate < 0.0f) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
} else {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
if (motors->init_targets_on_arming()) {
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
}
|
||||
#else
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
#endif
|
||||
|
@ -334,13 +334,17 @@ void Copter::ModeFlowHold::run()
|
||||
break;
|
||||
|
||||
case FlowHold_Landed:
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters do not spool down when landed. Only when commanded to go to ground idle by pilot.
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
#else
|
||||
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
|
||||
if (target_climb_rate < 0.0f) {
|
||||
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
} else {
|
||||
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
}
|
||||
|
||||
#endif
|
||||
copter.attitude_control->reset_rate_controller_I_terms();
|
||||
copter.attitude_control->set_yaw_target_to_current_heading();
|
||||
copter.attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(bf_angles.x, bf_angles.y, target_yaw_rate);
|
||||
|
@ -180,12 +180,17 @@ void Copter::ModeLoiter::run()
|
||||
break;
|
||||
|
||||
case Loiter_Landed:
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters do not spool down when landed. Only when commanded to go to ground idle by pilot.
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
#else
|
||||
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
|
||||
if (target_climb_rate < 0.0f) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
} else {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
}
|
||||
#endif
|
||||
loiter_nav->init_target();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
|
@ -184,12 +184,17 @@ void Copter::ModePosHold::run()
|
||||
|
||||
// if landed initialise loiter targets, set throttle to zero and exit
|
||||
if (ap.land_complete) {
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters do not spool down when landed. Only when commanded to go to ground idle by pilot.
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
#else
|
||||
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
|
||||
if (target_climb_rate < 0.0f) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
} else {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
}
|
||||
#endif
|
||||
loiter_nav->init_target();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
|
@ -130,13 +130,17 @@ void Copter::ModeSport::run()
|
||||
break;
|
||||
|
||||
case Sport_Landed:
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters do not spool down when landed. Only when commanded to go to ground idle by pilot.
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
#else
|
||||
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
|
||||
if (target_climb_rate < 0.0f) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
} else {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
}
|
||||
|
||||
#endif
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->input_euler_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate);
|
||||
|
@ -38,6 +38,8 @@ void Copter::ModeStabilize_Heli::run()
|
||||
set_land_complete(false);
|
||||
}
|
||||
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user