Browse Source

Copter: minor comment updates

No functional change
master
Randy Mackay 9 years ago
parent
commit
50e3c2ce3a
  1. 2
      ArduCopter/control_althold.cpp
  2. 4
      ArduCopter/control_autotune.cpp
  3. 4
      ArduCopter/control_poshold.cpp

2
ArduCopter/control_althold.cpp

@ -30,7 +30,7 @@ void Copter::althold_run() @@ -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);

4
ArduCopter/control_autotune.cpp

@ -243,7 +243,7 @@ bool Copter::autotune_start(bool ignore_checks) @@ -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() @@ -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);

4
ArduCopter/control_poshold.cpp

@ -82,7 +82,7 @@ bool Copter::poshold_init(bool ignore_checks) @@ -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() @@ -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…
Cancel
Save