XTRACK Error - which track?

When a rover reaches point A (technically, when it comes within WP_RADIUS of A) and does a pivot turn to navigate to B, does it attempt to navigate on the line between waypoint A and waypoint B, or, does it attempt to navigate on the line from where it turned (A’ in the below diagram) to point B? I have been looking at XTRACK error and it doesn’t always converge to 0 even when I turn up the XTRACK gain very high (like, 0.6 or 0.8).

image

What does rover use for the “previous” waypoint? Is the track the line from the previous waypoint to the next waypoint?

I really want my rover to come as close as possible to navigating on the line from A to B, even if it was not precisely at A when it stopped navigating to A and started navigating to B.

I also saw jimovonz’s comment here https://gitter.im/ArduPilot/ardupilot?at=5e17f92a9c13050f1fa49663

@jimovonz @rmackay9

1 Like

It will try to get onto the line between waypoint A and B regardless of whether it turns early or not.

Re the L1 xtrack I term, normally this is zero for Rovers I think. The turn rate and speed controllers have I-terms and I think these should be used instead.

How much error are you seeing in your xtrack? I have amended the Ardurover code to report average xtrack on the straights and on corners for each mission. Typically on a mission we would get better than 5cm average xtrack on the straights. We do not use any NAVL1_XTRACK_I for the reasons I cite in the link you posted. The main parameter that affects how aggressively your rover will stick to the line is NAVL1_PERIOD but how low you can set this value will depend on how well set up your rover is and how well it is tuned. We have motor controllers with inbuilt velocity control loops. Motor outputs from Ardurover are interpreted as a velocity requests. The motor controllers do a good job of maintaining the requested velocities with minimal lag. As such, we can calculate our ATC_STR_RAT_FF and ATC_SPEED_FF parameters precisely and get a very good tuning response. We have a NAVL1_PERIOD of 4.5 on these machines. I’m not sure how large your vehicles are but having the correct offset positions for your sensors can plays a big part. Also in our case, we have only been able to get a good response in the turns by having the primary GNSS module directly on the turn radius (in our case, directly between the two drive wheels). I believe that if the GNSS is forward or rearward of this location by any significant amount, then the accelerations reported throw off the EKF position and you end up with oscillation in the turning response. Is there any reason you WP_RADIUS needs to be anything other than some minimal distance? We use a value of 0.5 but we do not plan pivot turns - instead we plan multiple points in an arc of a given radius (our vehicle is capable of pivot turns by due to other considerations we do not plan them). Lately I have been trialling my high precision code changes along with higher GNSS position rates (25Hz) and some tweaks to the L1 controller. The results look promising - I had a number of runs in testing where the average xtrack error has been less than 2cm. This is on a 2.2 tonne vehicle that is 2.4m wide traveling at 10km/h.

Thanks @rmackay9 and @jimovonz!

Our vehicle is 200kg and 1.25 meters wide and traveling about 1 meter/sec. In most operations the rover is within 15 cm of where it should be (more on the xtrack error below). When mowing around trees I can reliably navigate 2 meter radius circles (using 12 waypoints in the circle) and they are thing of beauty. https://photos.app.goo.gl/euyVxw2wUV9F2Tsz9 I expect I could do even a 1.5 meter circle except the Mission Planner function to generate a WP circle only accepts an integer for the circle radius.

My mowing deck is 1.06 meters wide. Every cm of accuracy gains me 1% (i.e. 1cm/1.06meters) more productivity because I can reliably space the lengthwise tracks that much further apart. Also, of course, a wider deck will accomplish that, and a wider deck is planned for the next mower versions.

We too implemented motor controllers with inbuilt velocity control loops so that motor outputs from ardurover are interpreted as velocity requests; our motor controllers likewise do a good job of maintaining requested velocity. This was the single largest contributor to our current accuracy. We installed shaft encoders on each gearmotor. We do have slight slop in the sprocket-chain-sprocket connection between gearmotors and wheel axles which could contribute some loss of precision. (The next version of our mower uses hydraulic motors and encoders directly on the axles for much tighter control there).

We moved the primary GPS antenna to be directly between the two drive wheels for the reasons you mentioned. When pivoting it does not move more than about a cm. I’m intrigued by your comment about “accelerations reported”. We have not moved the accelerometers (i.e. the Pixhawk 4 itself) to be in the same central location - would you recommend that?

We are using pivot turns and getting good results.

(In case you’re wondering, Jim, as you and I have previously discussed this, I still don’t have the secondary GPS working and am still using the mag compass for heading). (Also, I set up an RTK base that is about 100-200 meters from my test fields, and observed a few cm of improvement over the prior base which was 21km distant; I read somewhere that the RTK error is about 1mm per km separation between rover and base).

Currently we are operating with WP_RADIUS of 0.2 meters.

Still, the largest xtrack I see is 0.3. (I assume the units are meters but have not seen that documented anywhere). When xtrack is that large, the autopilot always corrects. But even on long straights (30 meters or more) the autopilot doesn’t correct it all the way down to 0. Instead i often see it stabilize at .1 or .15 (or -0.1 or -0.15). Of course it jumps around a bit.

I am not familiar of how to calculate ATC_STR_RAT_FF and ATC_SPEED_FF. Do you mean following these steps? https://ardupilot.org/rover/docs/rover-tuning-steering-rate.html

Currently we are operating with ATC_STR_RAT_FF of 0.17, ATC_SPEED_FF of 0 (need to look into this!) and NAVL1_PERIOD of 7.5 (which is much longer than yours!). Looking at my other params is there anything that jumps out?
image

Jim, As soon as you’re ready for someone to test your code changes let me know; I would be happy to test them.

In my experience we have got the best results with the FC installed on the centre line of the vehicle and on the turning radius. The accelerations I was referring to were those reported by the GNSS

I understand what you are referring to when you refer to the xtrack ‘stabilising’ at some non zero offset. This is what I have tried to address in my latest changes. I believe that at these relatively small xtrack offsets, the output of the L1 controller is not strong enough.

The ATC_SPEED_FF parameter is not normally used, but in place of this the system uses the CRUISE_THROTTLE and CRUISE_SPEED parameters to determine the same proportion. If you have these set correctly then that is the equivalent. You can calculate these value based on your wheel diameter/rpm for a given throttle command. Because you have velocity controlled motors and have a linear response across the throttle range, it doesn’t matter what throttle value you choose for this setting. The same process can be done for the ATC_STR_RAT_FF setting. This parameter is essentially the amount of steering input to achieve a turning rate of 1 rad/s. Using your same wheel diam and wheel separation you can calculate how much throttle differential you need to achieve this 1 rad/s. It is this throttle value that you use for this parameter (where 1.0 = 100% throttle). Once you have these parameters set, you can dial right back on the ATC_STR_RATE_P and the ATC_SPEED_P values.

I would try to work on reducing the NAVL1_PERIOD. If this is set too low then you will observe the rover oscillating about the path as it over shoots and over corrects.

If you are still having problems with the moving baseline GNSS setup, I have recently implemented heading from dual independent GNSS. We run a local basestation and both GNSS on the vehicle get RTK corrections. Using the position from these two modules and the geometry stored in the GPS_POSXXX params, I calculate the heading. With a seperation of 1.3m I see an accuracy of ~0.5 deg but without the high precision code I would expect the error to double. In this configuration you can also crank up the F9P reporting rate (rtk at up to ~40Hz with code changes)