ArduPilot / ardupilot

ArduPlane, ArduCopter, ArduRover, ArduSub source
http://ardupilot.org/
GNU General Public License v3.0
10.69k stars 17.16k forks source link

Copter: is this a bug in AC_WPNav::advance_wp_target_along_track at old version? #24796

Open luweiagi opened 1 year ago

luweiagi commented 1 year ago

@lthall Hi, I sometimes still read the old version code, and make a contrast with the newest version. When I see the function of AC_WPNav::advance_wp_target_along_track() in the old code version, https://github.com/ArduPilot/ardupilot/blob/25f1a4a4e1e5ccc10c744ff4b6028e27079aabe1/libraries/AC_WPNav/AC_WPNav.cpp#L446

        // increase intermediate target point's velocity if not yet at the leash limit
        if(dt > 0 && !reached_leash_limit) {
            _limited_speed_xy_cms += 2.0f * _track_accel * dt;
        }

I am confused that why there is a number 2? because the formular is: v_t = v_0 + a dt NOT v_t = v_0 + 2 a * dt So, why there is a number 2? I guess you multiply 2 for the reason of making _track_accel bigger? But if for this reason, why not directly increase _track_accel itself?

lthall commented 1 year ago

Oh wow. That is going back in time :)

This factor of two is because the aircraft moves on a leash or rubber band defined by the stopping distance. We moved by moving the target point out in front of the aircraft so at any time we could stop moving that point and the aircraft could stop as it reached that point using the maximum acceleration.

When starting from stationary we need to move the point off out in front of the aircraft. However, because the aircraft moves slower than that point we need to use 2 x the acceleration to get the aircraft to move off at 1 x the acceleration.