From c32a70763254fb22a6a32d2dea62ed62854b5d7e Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 1 Nov 2011 09:28:36 -0700 Subject: [PATCH] cleanup --- ArduCopter/ArduCopter.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 9772008965..113dbe5a4a 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1240,7 +1240,7 @@ static void update_altitude() current_loc.alt = baro_alt + home.alt; } - // calc the accel rate limit to 2m/s + // calc the vertical accel rate int temp_rate = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale altitude_rate = (temp_rate - old_rate) * 10; old_rate = temp_rate; @@ -1251,6 +1251,7 @@ static void adjust_altitude() { /* + // old vert control if(g.rc_3.control_in <= 200){ next_WP.alt -= 1; // 1 meter per second next_WP.alt = max(next_WP.alt, (current_loc.alt - 500)); // don't go less than 4 meters below current location