mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Rename set_yaw_target_to_current_heading
This commit is contained in:
parent
34e342f658
commit
3b0a870504
@ -458,7 +458,7 @@ void Mode::make_safe_spool_down()
|
||||
case AP_Motors::SpoolState::GROUND_IDLE:
|
||||
// relax controllers during idle states
|
||||
attitude_control->reset_rate_controller_I_terms_smoothly();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
break;
|
||||
|
||||
case AP_Motors::SpoolState::SPOOLING_UP:
|
||||
|
@ -45,12 +45,12 @@ void ModeAltHold::run()
|
||||
|
||||
case AltHold_MotorStopped:
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
break;
|
||||
|
||||
case AltHold_Landed_Ground_Idle:
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
FALLTHROUGH;
|
||||
|
||||
case AltHold_Landed_Pre_Takeoff:
|
||||
|
@ -50,7 +50,7 @@ void AutoTune::run()
|
||||
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
}
|
||||
copter.attitude_control->reset_rate_controller_I_terms_smoothly();
|
||||
copter.attitude_control->set_yaw_target_to_current_heading();
|
||||
copter.attitude_control->reset_yaw_target_and_rate();
|
||||
|
||||
float target_roll, target_pitch, target_yaw_rate;
|
||||
get_pilot_desired_rp_yrate_cd(target_roll, target_pitch, target_yaw_rate);
|
||||
|
@ -91,13 +91,13 @@ void ModeDrift::run()
|
||||
switch (motors->get_spool_state()) {
|
||||
case AP_Motors::SpoolState::SHUT_DOWN:
|
||||
// Motors Stopped
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
break;
|
||||
|
||||
case AP_Motors::SpoolState::GROUND_IDLE:
|
||||
// Landed
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms_smoothly();
|
||||
break;
|
||||
|
||||
|
@ -263,7 +263,7 @@ void ModeFlowHold::run()
|
||||
case AltHold_MotorStopped:
|
||||
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||
copter.attitude_control->reset_rate_controller_I_terms();
|
||||
copter.attitude_control->set_yaw_target_to_current_heading();
|
||||
copter.attitude_control->reset_yaw_target_and_rate();
|
||||
copter.pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
flow_pi_xy.reset_I();
|
||||
break;
|
||||
@ -285,7 +285,7 @@ void ModeFlowHold::run()
|
||||
break;
|
||||
|
||||
case AltHold_Landed_Ground_Idle:
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
FALLTHROUGH;
|
||||
|
||||
case AltHold_Landed_Pre_Takeoff:
|
||||
|
@ -115,7 +115,7 @@ void ModeLoiter::run()
|
||||
|
||||
case AltHold_MotorStopped:
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
loiter_nav->init_target();
|
||||
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate);
|
||||
@ -141,7 +141,7 @@ void ModeLoiter::run()
|
||||
break;
|
||||
|
||||
case AltHold_Landed_Ground_Idle:
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
FALLTHROUGH;
|
||||
|
||||
case AltHold_Landed_Pre_Takeoff:
|
||||
|
@ -101,7 +101,7 @@ void ModePosHold::run()
|
||||
|
||||
case AltHold_MotorStopped:
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
loiter_nav->clear_pilot_desired_acceleration();
|
||||
loiter_nav->init_target();
|
||||
@ -141,7 +141,7 @@ void ModePosHold::run()
|
||||
loiter_nav->clear_pilot_desired_acceleration();
|
||||
loiter_nav->init_target();
|
||||
loiter_nav->update(false);
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
init_wind_comp_estimate();
|
||||
FALLTHROUGH;
|
||||
|
||||
|
@ -75,7 +75,7 @@ void ModeSport::run()
|
||||
|
||||
case AltHold_MotorStopped:
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
break;
|
||||
|
||||
@ -93,7 +93,7 @@ void ModeSport::run()
|
||||
break;
|
||||
|
||||
case AltHold_Landed_Ground_Idle:
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
FALLTHROUGH;
|
||||
|
||||
case AltHold_Landed_Pre_Takeoff:
|
||||
|
@ -31,13 +31,13 @@ void ModeStabilize::run()
|
||||
switch (motors->get_spool_state()) {
|
||||
case AP_Motors::SpoolState::SHUT_DOWN:
|
||||
// Motors Stopped
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
break;
|
||||
|
||||
case AP_Motors::SpoolState::GROUND_IDLE:
|
||||
// Landed
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms_smoothly();
|
||||
break;
|
||||
|
||||
|
@ -50,14 +50,14 @@ void ModeStabilize_Heli::run()
|
||||
switch (motors->get_spool_state()) {
|
||||
case AP_Motors::SpoolState::SHUT_DOWN:
|
||||
// Motors Stopped
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
break;
|
||||
case AP_Motors::SpoolState::GROUND_IDLE:
|
||||
// If aircraft is landed, set target heading to current and reset the integrator
|
||||
// Otherwise motors could be at ground idle for practice autorotation
|
||||
if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) {
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms_smoothly();
|
||||
}
|
||||
break;
|
||||
|
@ -131,7 +131,7 @@ void ModeSystemId::run()
|
||||
switch (motors->get_spool_state()) {
|
||||
case AP_Motors::SpoolState::SHUT_DOWN:
|
||||
// Motors Stopped
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
break;
|
||||
|
||||
@ -140,7 +140,7 @@ void ModeSystemId::run()
|
||||
// Tradheli initializes targets when going from disarmed to armed state.
|
||||
// init_targets_on_arming is always set true for multicopter.
|
||||
if (motors->init_targets_on_arming()) {
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms_smoothly();
|
||||
}
|
||||
break;
|
||||
|
@ -114,7 +114,7 @@ void ModeThrow::run()
|
||||
}
|
||||
|
||||
// demand zero throttle (motors will be stopped anyway) and continually reset the attitude controller
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_throttle_out(0,true,g.throttle_filt);
|
||||
break;
|
||||
@ -129,7 +129,7 @@ void ModeThrow::run()
|
||||
}
|
||||
|
||||
// Hold throttle at zero during the throw and continually reset the attitude controller
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_throttle_out(0,true,g.throttle_filt);
|
||||
|
||||
|
@ -326,7 +326,7 @@ void ModeZigZag::manual_control()
|
||||
|
||||
case AltHold_MotorStopped:
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
loiter_nav->init_target();
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
|
||||
@ -352,7 +352,7 @@ void ModeZigZag::manual_control()
|
||||
break;
|
||||
|
||||
case AltHold_Landed_Ground_Idle:
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
FALLTHROUGH;
|
||||
|
||||
case AltHold_Landed_Pre_Takeoff:
|
||||
|
@ -18,6 +18,6 @@ void Copter::standby_update()
|
||||
}
|
||||
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
pos_control->standby_xyz_reset();
|
||||
}
|
||||
|
@ -123,7 +123,7 @@ void Mode::auto_takeoff_run()
|
||||
wp_nav->shift_wp_origin_and_destination_to_current_pos_xy();
|
||||
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
|
||||
pos_control->update_z_controller();
|
||||
attitude_control->set_yaw_target_to_current_heading();
|
||||
attitude_control->reset_yaw_target_and_rate();
|
||||
attitude_control->reset_rate_controller_I_terms();
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user