AC: reducing twitches in Loiter, RTL

378 views
Skip to first unread message

Randy Mackay

unread,
May 8, 2014, 4:01:59 AM5/8/14
to drones-...@googlegroups.com

 

      Leonard and I spent the past few days getting rid of various twitches.  The places where we were able to make progress were:

·         Twitch when changing from Hybrid to Loiter (both vertical and horizontal twitches were found and fixed)

·         Twitch when flying at high speed and changing into Loiter, Guided, RTL (and probably Auto).

 

     Attached is a graph of the difference in the navigation controller’s desired pitch angle when someone engages RTL from a high speed.

 

In the “BEFORE” diagram you can see the vehicle starts the test by flying forward at full speed, leaning 45deg forward.  RTL is engaged and the vehicle immediately leans completely back at 45deg.  It’s at this point that badly tuned copters completely flip over.  The vehicle then find it’s slowed down too much and reduces its lean back and eventually it finds that it’s stopped too quickly and actually leans forward again a bit before returning home.

 

In the “After” diagram you can see that the vehicle first reduces its lean angle quickly from 45deg -> 20 deg.  At this point the wind drag alone slows the copter very quickly.  It keeps reducing its lean angle and then finally it leans back for a moment to stop at the target stopping point and then leans back again as it returns home.   It’s still not ideal but it’s much better than what we had before.

 

     By the way, there’s a new parameter called WPNAV_LOIT_JERK which controls the change in acceleration while in Loiter mode.  Currently it’s defaults to 1000 (10m/s/s/s) but you can try it at 2000 if you find it sluggish.

 

-Randy

Pitch_during_RTL_BeforeAfterpng.png

Maurice Barnes

unread,
May 8, 2014, 7:58:27 AM5/8/14
to drones-...@googlegroups.com

Randy would these changes impact the twitching at waypoints in Auto?

Regards,
Maurice

--
You received this message because you are subscribed to the Google Groups "drones-discuss" group.
To unsubscribe from this group and stop receiving emails from it, send an email to drones-discus...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Randy Mackay

unread,
May 8, 2014, 8:19:57 AM5/8/14
to drones-...@googlegroups.com

Maurice,

 

     I’m not sure.  There is still a small twitch as it passes through spline waypoints and I believe we know the cause of that and will fix it before the big AC3.2 release.  I’m less sure about straight line waypoints but I’ll run it through the simulator and see.  Is this your report about the issue for straight line waypoints?

                https://github.com/diydrones/ardupilot/issues/1012

 

-Randy

Maurice Barnes

unread,
May 8, 2014, 8:33:51 AM5/8/14
to drones-...@googlegroups.com
That's pretty much the same issue I am having. I mainly fly Spline now and as you have said the problem exists. When you get around to the fix I will be more than happy to test. I have noticed in recent Masters a problem with Yawing as the copter approached a waypoint seems to have disappeared. 

Regards,
Maurice

Holger Steinhaus

unread,
May 8, 2014, 2:01:49 PM5/8/14
to drones-...@googlegroups.com
Hi Randy,

I did some testing based on 73dc32108 today. During the flight I made some notes, I just copy them here. Later I will upload the logs.

LOITER_JERK: values around 3000 gives a smooth and decent acceleration and deceleration behavior with my rather agile 15"/2kg quad and my favourized  LOITER_SPEED  of 16m/s. I do not like lower JERK values, they feel somehow dangerous in low altitudes (e.g. during landings in LOITER), as I have the impression that there is not enough lateral control.

Twitching: During Loiter, there is exactly one situation with noticeable twitching: while the copter is rotating with a high angular rate (roll or pitch). As soon as the copter is near its desired angle and therefore reduces its angular rate, the twitch stops very suddenly. You can trigger that behavior by setting rather large LOITER_JERK values (2000..9000) and moving the stick forward and backward with a period of about 0.5...1 Hz. Flying lower JERK values masks the twitch, as the copter does not reach the angular speed that is required for twitching. There seems to be some dependency from battery voltage - with full batteries the twitch is worse. There is absolutely no twitching in ALT_HOLD under any circumstances and any battery level. I did not notice any twitch on the FPV screen during high speed loitering, as I did three weeks ago.

RTL: I think, there is some kind of regression regarding the twitching during the initial RTL climb. Some days ago I was sure that the issue was resolved. Today I had an really intensive low-frequency twitch in the first part of the RTL climb. My RLT alt is set to 200m, as I have some high obstacles around (wind turbines). So may be in the later part of the climb the copter was still twitching, but I was just unable to hear it.

Holger

Randy Mackay

unread,
May 8, 2014, 8:15:12 PM5/8/14
to drones-...@googlegroups.com

Holger,

 

     Thanks for the testing.

 

     Any chance you have a dataflash log file?  In particular I’d like to see what’s happening during the RTL.  I haven’t been able to reproduce an issue but that doesn’t mean it’s not there, I just can’t find it.

 

-Randy

--

Holger Steinhaus

unread,
May 9, 2014, 3:50:22 AM5/9/14
to drones-...@googlegroups.com
Hi Randy,

sorry, I was a bit short of time yesterday. Here are the logs: https://www.dropbox.com/s/mj2f4dicjqlcf8g/qh2-20140508-test.zip The RTL should be flight 3 or 4. 

Flight description:
#13 LOITER_JERK testing and tuning
#14: General Loiter tests (twitching), comparison to ALT_HOLD and STABILIZE
#15: Hybrid mode
#16: RTL

Holger
Reply all
Reply to author
Forward
0 new messages