mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: remove some comments from althold
This commit is contained in:
parent
a642c88e34
commit
15c57342a5
@ -82,14 +82,6 @@ void Copter::althold_run()
|
||||
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// call throttle controller
|
||||
// ToDo: Should we really run surface_tracking during takeoff?
|
||||
// if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
// target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
// }
|
||||
|
||||
// call position controller
|
||||
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt, false);
|
||||
@ -112,7 +104,6 @@ void Copter::althold_run()
|
||||
case AltHold_Flying:
|
||||
// call attitude controller
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// call throttle controller
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
|
Loading…
Reference in New Issue
Block a user