Copter: WPNav consolidate acceleration #defines

This commit is contained in:
Randy Mackay 2013-05-27 10:36:24 +09:00
parent d510f8f722
commit dbd6524f9f
2 changed files with 1 additions and 3 deletions

View File

@ -380,7 +380,7 @@ void AC_WPNav::advance_target_along_track(float dt)
}else{
// increase intermediate target point's velocity if not yet at target speed (we will limit it below)
if(dt > 0 && _limited_speed_xy_cms < _wp_speed_cms) {
_limited_speed_xy_cms += WPNAV_WP_ACCELERATION * dt;
_limited_speed_xy_cms += 2.0f * WPNAV_ACCELERATION * dt;
}
// do not go over top speed
if(_limited_speed_xy_cms > _wp_speed_cms) {

View File

@ -31,8 +31,6 @@
#define WPNAV_ALT_HOLD_P 2.0f // hard coded estimate of throttle controller's altitude hold's P gain. To-Do: retrieve gain from throttle controller
#define WPNAV_ALT_HOLD_ACCEL_MAX 250.0f // hard coded estimate of throttle controller's maximum acceleration in cm/s. To-Do: retrieve from throttle controller
#define WPNAV_WP_ACCELERATION 500.0f // acceleration in cm/s/s used to increase the speed of the intermediate point up to it's maximum speed held in _speed_xy_cms
#define WPNAV_MIN_LEASH_LENGTH 100.0f // minimum leash lengths in cm
class AC_WPNav