Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Updated TradHeli swashplate behaviors while on ground; fixes issue #5396 #7136

Merged
merged 2 commits into from Oct 28, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
20 changes: 18 additions & 2 deletions ArduCopter/control_althold.cpp
Expand Up @@ -74,18 +74,24 @@ void Copter::althold_run()

motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading();
#if FRAME_CONFIG == HELI_FRAME
// force descent rate and call position controller
pos_control->set_alt_target_from_climb_rate(-abs(g.land_speed), G_Dt, false);
heli_flags.init_targets_on_arming=true;
#else
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading();
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
#endif
pos_control->update_z_controller();
break;

case AltHold_Takeoff:
#if FRAME_CONFIG == HELI_FRAME
if (heli_flags.init_targets_on_arming) {
heli_flags.init_targets_on_arming=false;
}
#endif
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);

Expand Down Expand Up @@ -121,8 +127,18 @@ void Copter::althold_run()
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}

#if FRAME_CONFIG == HELI_FRAME
if (heli_flags.init_targets_on_arming) {
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading();
if (motors->get_interlock()) {
heli_flags.init_targets_on_arming=false;
}
}
#else
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading();
#endif
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
pos_control->update_z_controller();
Expand Down
8 changes: 5 additions & 3 deletions ArduCopter/heli_control_acro.cpp
Expand Up @@ -35,12 +35,14 @@ void Copter::heli_acro_run()

if(!motors->armed()) {
heli_flags.init_targets_on_arming=true;
attitude_control->set_yaw_target_to_current_heading();
attitude_control->set_attitude_target_to_current_attitude();
attitude_control->reset_rate_controller_I_terms();
}

if(motors->armed() && heli_flags.init_targets_on_arming) {
attitude_control->set_yaw_target_to_current_heading();
if (motors->rotor_speed_above_critical()) {
attitude_control->set_attitude_target_to_current_attitude();
attitude_control->reset_rate_controller_I_terms();
if (motors->get_interlock()) {
heli_flags.init_targets_on_arming=false;
}
}
Expand Down
4 changes: 3 additions & 1 deletion ArduCopter/heli_control_stabilize.cpp
Expand Up @@ -35,11 +35,13 @@ void Copter::heli_stabilize_run()
if(!motors->armed()) {
heli_flags.init_targets_on_arming=true;
attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms();
}

if(motors->armed() && heli_flags.init_targets_on_arming) {
attitude_control->set_yaw_target_to_current_heading();
if (motors->rotor_speed_above_critical()) {
attitude_control->reset_rate_controller_I_terms();
if (motors->get_interlock()) {
heli_flags.init_targets_on_arming=false;
}
}
Expand Down
3 changes: 3 additions & 0 deletions libraries/AC_AttitudeControl/AC_AttitudeControl.h
Expand Up @@ -107,6 +107,9 @@ class AC_AttitudeControl {
// reset rate controller I terms
void reset_rate_controller_I_terms();

// Sets attitude target to vehicle attitude
void set_attitude_target_to_current_attitude() { _attitude_target_quat.from_rotation_matrix(_ahrs.get_rotation_body_to_ned()); }

// Sets yaw target to vehicle heading
void set_yaw_target_to_current_heading() { shift_ef_yaw_target(degrees(_ahrs.yaw - _attitude_target_euler_angle.z)*100.0f); }

Expand Down