From 50e3c2ce3a5e6d2b6686e1dcc2824fc4a43911b8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 18 Nov 2015 22:07:42 +0900 Subject: [PATCH] Copter: minor comment updates No functional change --- ArduCopter/control_althold.cpp | 2 +- ArduCopter/control_autotune.cpp | 4 ++-- ArduCopter/control_poshold.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/control_althold.cpp b/ArduCopter/control_althold.cpp index 48c68b11a5..c531e893f3 100644 --- a/ArduCopter/control_althold.cpp +++ b/ArduCopter/control_althold.cpp @@ -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); diff --git a/ArduCopter/control_autotune.cpp b/ArduCopter/control_autotune.cpp index 2f8f4757e8..8de09f4c22 100644 --- a/ArduCopter/control_autotune.cpp +++ b/ArduCopter/control_autotune.cpp @@ -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); diff --git a/ArduCopter/control_poshold.cpp b/ArduCopter/control_poshold.cpp index 83d469cb10..309bd3de75 100644 --- a/ArduCopter/control_poshold.cpp +++ b/ArduCopter/control_poshold.cpp @@ -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);