Loiter Runaway in TradHeli

@bnsgeyer @Leonardthall Recent master of Trad Heli…all PSC params default…heli has been tuned , although not perfectly, in roll and pitch, pretty well in yaw…behaves well in STAB/ALTHLD and most of the time in Loiter, although its very “loose”, in that demanded position changes from the stick do not halt well …kinda slides around a bit…but that is not the big problem…occasionally it will runaway from its loiter position showing large uncommanded target position changes and following them (very well) and while doing so ignores stick inputs trying to counteract them…see the video below:

log : https://www.dropbox.com/s/wgdge5tz30u8qpf/2021-06-28%2013-56-51.bin?dl=0

apparently, its not due to EKF going bad…no bad innovations:

Won’t have a chance to look at this until later this weekend. I was trying to look at the video but it says it is private and wouldn’t let me view it.

This heli was able to take off with zero collective and without requesting a positive climb rate.

I suspect you have not set up zero collective correctly.

Not sure what data signal you are looking at but he is using a 3D setup. So his raw collective settings may be different from what we are use to seeing. I am away from home right now with no access to a computer. I will look at it when I return.

1 Like

sorry,had the wrong tag…should be viewable now

Hey Henry,

If this has been happening regularly could you try to climb next time you see this?

My theory is that you are still in the landed state because you have not commanded a climb yet but have taken off because of a high zero collective. If you command a climb the aircraft should detect a take off and you should get normal loiter control.

Funny you say that because I swear I heard my TX say “landed” just before it started drifting (using Yaapu telem script on my TX), but could never find a GCS message in the log…maybe it’s an “event” recorded? Maybe the land detection falsely triggered?Will try your suggestion when I get back…it has happened before…
The manual servo setup collective param points are set to -10/0/+10…the Stabilize curve is -3 to +8, but that should not be in play

Could you post your parameters? Do you have H_COL_MID set correctly?

myparams.param (18.8 KB)

I set H_COL_MID for 0deg with pitch gauge(at every blade rotation position)…but looking at H_COLL_HOVER it shows its learned( or rather has not learned) .38 instead of something like .75 as I would expect…I will recheck everything when I get back…before this flight I shortened the mechanical throws to minimum on all swash servo links to get a wider servo throw for the pitch range (this heli has ridiculous coll range),perhaps I messed up the pitch somehow even though I spent a lot of time getting it setup again…

btw its easy to extract the params and their changes from the log with MP, just click “show params” on log review screen…can save to a file also

Yeah I know but I am still away from a computer and this would allow me to look at them on my phone.

So I looked at the log, I spooled up in Loiter and immediately was getting landed maybe events as I lifted off into low loiter and then moved it away from me…then it gave a land_complete and took off diagonally behind me and climbing slowly, then I switched to STABILIZE to get control and NOT_LANDED event was signaled…so Leonard was right it was in LANDED state…

however, I did have to raise throttle stick to get it to climb initially from the ground (almost 1800us)…it did not do that by itself…it was at 1475 all the time I was moving it away from me at level low altitude and during the time it declared LAND_COMPLETE…after which it drifted off

I rechecked my collective, very carefully again, and mid was indeed a little off ~1deg positive at mid…and it appears that this thing hovers at about 2.5deg positive, not 4-5deg, based on the 40% hover point…the overall range was -2 to +8.5 (I remember now that I decreased it back to standard when I shortened throws wanting to get everything perfect before going to the full -10 to +10 range)…

I dont think we should be land detecting if the mid point is only off a degree…seems too sensitive to me…

I think that I finally understand the importance of the H_COL_MIN…I was thinking it was a pitch curve point (and it has nothing to do with that I now understand) , and MUST be ~ zero or a little negative thrust… it sets the ground idle collective in altitude controlled modes AND is a prime decision point for the landing detector in heli…since my heli hovers at very low pitch being an aggressive 3D design (I was used to flybar designs with lower head speed and a 5deg hover), and I did not have the heli leveled well enough when I measured mid collective (it was +1deg instead of 0)…hover was at 30% of the total range or slightly above H_COL_MID (24% of range)…enough to allow many land maybe detects as the collective was being controlled and eventually a land complete was detected while still hovering…

subsequently I readjusted my H_COL values a little bit, primarily the mid point to get exactly 0deg, and test flew…hover collective was 47% (again 2.5deg) and was well above H_COL_MID (which was 26% of full range) and no 'land maybes" happen in the short test loiter now…

perhaps we should set the decision point a bit lower than 0 thrust and a bit into the negative thrust range? and/or advise to set Collective Mid to 1 deg negative to give some margin? would a degree negative create bad ground shakes on big vehicles? And stessing the importance of having the hover _coll wind up being 50% (or more) of the range, ie close to .5 for standard setups, should be added to the wiki…like doing an althold test to get it learned and compared to mid coll before loitering?

@hwurzburg I assume you mean H_COL_MID.

H_COL_MID is dual use. Originally it was only used for the collective to yaw mixing but then Chris and I also replaced H_LAND_COL_MIN with H_COL_MID to designate the lowest point collective should be while landed in non-manual collective modes. I think many misinterpret this parameter as setting the midpoint of a collective curve. The collective curve (if you want to call it that) in all modes but stabilize is a straight line from H_COL_MIN to H_COL_MAX.

You were fortunate to determine that your H_COL_MID was too high. If it is too high, it can (and has) cause auto disarm in-flight in RTL or land modes because it thought it was landed prematurely. You see, in most cases the ambient wind cause the hover collective to be lower and it drops below the H_COL_MID value and if all the other landing detector conditions are met then it declares the aircraft is landed.

So regarding the idea of setting it lower, it depends if you are using the collective to yaw mixing. If you aren’t, then setting it slightly lower than 0 deg collective, would probably be ok. With the new integrator management scheme, it does use H_COL_MID to determine when the collective is 50% hover collective so it can release the integrator. Therefore setting it lower would mean the integrator would be released sooner and there would be more weight on the skids. This could cause the integrator to build more before lift off and may require some corrections by the pilot after liftoff due to the integrator building too much.

@hwurzburg,
I hadn’t looked at the log since I thought that you figured this out. On your initial attempt to go into loiter from a hover, the landing detector did declare that you had landed based on the H_COL_MID being set too high. Thus once you switched into loiter, you had no control. Although throttle out (collective out for heli) CTUN.ThO was showing zero, this is not the case for heli. In the motors class, the collective is limited to going no lower than H_COL_MID. Therefore you heli was able to hold a hover with H_COL_MID set.


So at the point you see the ThO drop to zero, it actually went to 0.24. How windy was it that day? Did you have a pretty high steady wind? That would explain why you were able to hover at the lower than expected collective setting. However like you determined, H_COL_MID was not a zero thrust collective setting and thus the heli was able to hover.

You asked about why we get land complete maybe events on takeoffs in loiter. This happens regardless of whether H_COL_MID is set properly or not. It has to do with the fact that the throttle (collective) in the greater code starts at zero and in the motors class it is kept at H_COL_MID. So the greater code has to raise the throttle (collective) from zero to the value that corresponds to H_COL_MID which takes a substantial amount of time that allows the landing detection code to spit out a few land complete maybes before lift off. I would probably need @Leonardthall help to fix this issue.

I think the first problem here is zero throttle is supposed to be zero thrust. So H_COL_MID should be zero Throttle. We would need to restructure the Accel PID initialisation code to support non-zero zero thrust. It is probably simpler in the long run to keep zero = zero.

I suspect what happened was heli added support for negative collective but just moved zero to full negative collective.

If we got this right you should be able to run roll/pitch rate input for Alt hold and do continuous rolls and Alt Hold should hold altitude reasonably well. (it will bob up and down) As the aircraft goes upside down the frame conversion from vertical to collective should swap the sign of the throttle/thrust output. Further the value of thrust/throttle when inverted should be identical but negative of normal flight.

For the landing detector the tests we have are:

  • motor_at_lower_limit - minimum permissible thrust, assuming the aircraft can and will descend reliably under all but the most extreme conditions.
  • accel_stationary - Stable on the ground - the assumption being that under extreme conditions the aircraft will also be moving around and therefore this check will catch most cases that get past the first check.
  • descent_rate_low - Not descending despite being at the minimum lift case.

If we have zero lift force, perfectly stable and not descending then it is impossible for us to tell that we are not landed.

The problem here, like quadplane, it was possible to be stable, not descending and at minimum thrust.

We also have a “land maybe” flag that gives us the potential of changing a state that would making landing detection easier. For example we could remove any throttle restrictions based on roll and pitch. Limit output commands that may increase the aircraft’s lift. Plane could add maximum negative flap for example. Multirotor could relax the yaw controller.

Post moved to DM to keep things organised. wrong location.

Your first dropbox link there doesnt work as intended
I remember looking at that log for the Y6, cant remember the outcome if any, I’ll try to find it again

1 Like

Post moved to DM to keep things organised. wrong location.

We don’t endorse drug use :laughing:
Sorry to sidetrack a very technical discussion, coudn’t help it.

1 Like

Good to see a little fun once and awhile!