diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index d31a65669a..de499acfc8 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -199,7 +199,7 @@ static void calc_nav_rate(int max_speed) x_rate_error = constrain(x_rate_error, -1000, 1000); nav_lon = g.pid_nav_lon.get_pid(x_rate_error, dTnav); temp = x_target_speed * x_target_speed; - temp *= .0054; + temp *= g.tilt_comp; if(x_target_speed < 0) temp = -temp; @@ -212,7 +212,7 @@ static void calc_nav_rate(int max_speed) y_rate_error = constrain(y_rate_error, -1000, 1000); // added a rate error limit to keep pitching down to a minimum nav_lat = g.pid_nav_lat.get_pid(y_rate_error, dTnav); temp = y_target_speed * y_target_speed; - temp *= .0054; + temp *= g.tilt_comp; if(y_target_speed < 0) temp = -temp; @@ -261,7 +261,7 @@ static int16_t calc_desired_speed(int16_t max_speed, bool _slow) // limit the ramp up of the speed // waypoint_speed_gov is reset to 0 at each new WP command if(max_speed > waypoint_speed_gov){ - waypoint_speed_gov += (int)(100.0 * dTnav); // increase at .5/ms + waypoint_speed_gov += (int)(200.0 * dTnav); // increase at .5/ms max_speed = waypoint_speed_gov; }