mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: minor comment updates
No functional change
This commit is contained in:
parent
945bdee452
commit
50e3c2ce3a
@ -30,7 +30,7 @@ void Copter::althold_run()
|
||||
AltHoldModeState althold_state;
|
||||
float takeoff_climb_rate = 0.0f;
|
||||
|
||||
// initialize vertical speeds and leash lengths
|
||||
// initialize vertical speeds and acceleration
|
||||
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
pos_control.set_accel_z(g.pilot_accel_z);
|
||||
|
||||
|
@ -243,7 +243,7 @@ bool Copter::autotune_start(bool ignore_checks)
|
||||
return false;
|
||||
}
|
||||
|
||||
// initialize vertical speeds and leash lengths
|
||||
// initialize vertical speeds and acceleration
|
||||
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
pos_control.set_accel_z(g.pilot_accel_z);
|
||||
|
||||
@ -262,7 +262,7 @@ void Copter::autotune_run()
|
||||
float target_yaw_rate;
|
||||
int16_t target_climb_rate;
|
||||
|
||||
// initialize vertical speeds and leash lengths
|
||||
// initialize vertical speeds and acceleration
|
||||
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
pos_control.set_accel_z(g.pilot_accel_z);
|
||||
|
||||
|
@ -82,7 +82,7 @@ bool Copter::poshold_init(bool ignore_checks)
|
||||
return false;
|
||||
}
|
||||
|
||||
// initialize vertical speeds and leash lengths
|
||||
// initialize vertical speeds and acceleration
|
||||
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
pos_control.set_accel_z(g.pilot_accel_z);
|
||||
|
||||
@ -136,7 +136,7 @@ void Copter::poshold_run()
|
||||
float vel_fw, vel_right; // vehicle's current velocity in body-frame forward and right directions
|
||||
const Vector3f& vel = inertial_nav.get_velocity();
|
||||
|
||||
// initialize vertical speeds and leash lengths
|
||||
// initialize vertical speeds and acceleration
|
||||
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
pos_control.set_accel_z(g.pilot_accel_z);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user