QuadPlane slowly moving forward in a jerky way

More fun with the QuadPlane today. I tried a simple mission in AUTO with a VTOL_TAKEOFF and a WAYPOINT about 250 meters away. The takeoff works well but then when the plane is supposed to transition and move towards the waypoint, it does so in a strange and ineffective way by applying ~80% throttle to the push motor every 3 seconds or so, in spikes.

Looking at the above graph, something seems wrong with the red line RCOU.C3. The transition to fixed-wing never happens as the plane isn’t able to pick up enough speed. Light headwind 5mph or so.

I tried to add/force a DO_VTOL_TRANSITION 4 between the takeoff and the WP, which doesn’t help.

Some parameters that I tweaked but didn’t help:

Q_GUIDED_MODE,0
THR_MAX,100
THR_MIN,0
TRIM_THROTTLE,100

PARAM file: https://dl.dropboxusercontent.com/u/67653/share/quadplane-2016-10-03.param.txt
BIN log: https://dl.dropboxusercontent.com/u/67653/share/quadplane-2016-10-03.BIN

@tridge any idea what is happening? Some help would be immensely appreciated.

@GregCovey I know you’ve successfully completed an AUTO mission, have you encountered this issue?

Thanks.

EDIT: all the following modes work well: QSTABILIZE, QHOVER, QLOITER, FBWA, CRUISE.
EDIT2: RCIN should be irrelevant, it was probably just me getting ready to take over.
EDIT3: I see there’s a param called Q_WP_SPEED but I can’t find any information anywhere including in the code. It’s currently set at 500 (cm/s I assume), is this the issue?

Anthony,

I haven’t seen this issue. Here are a few differences I noticed in my plan from yours. I’m not sure if they mean anything.

  1. I did not use a parameter 4 after my DO_VTOL_TRANSITION command.
  2. My VTOL_TAKEOFF has Lat/Long values for Home.
  3. I am using APM Plane v3.6.0

@Anthony, this is caused by a bug that I am working on fixing today. The quadplane code doesn’t handle transitions correctly without an airspeed sensor. Your log shows your airspeed sensor is disabled (as ARSPD_USE=0).
I should have a fix for you to test soon!

@Anthony I have pushed a fix into master. It is building on the autobuild servers now and should be ready to test in a couple of hours

1 Like

Thanks @tridge.

For reference, as I mentioned on the chat, in the meantime I tried with ARSPD_USE=1 and the transition works better. I had some issues with my airspeed sensor but this was due to a leak in one of the tubes. After it was fixed and re-calibrated, the issue went away.

@Anthony I notice you have TRIM_THROTTLE=100 in the log. That will give pretty crazy throttle results. I also notice that when fwd motor was at 100% the plane did not respond with expected forward acceleration. Is the motor setup ok?

@Anthony I have looked at your log quadplane-2016-10-04.BIN
Some notable problems:

  • it has TRIM_THROTTLE=100, which makes no sense. Can you really only achieve cruise speed at full throttle?
  • at full throttle with the nose down the plane did not gain speed. That makes no sense. Is the fwd motor really working? Is it appropriately sized?
  • you had THROTTLE_NUDGE=1 and had the throttle stick pushed to max. That means it was aiming for a airspeed of ARSPD_FBW_MAX which was 25. It clearly can’t achieve that. Are you aware of how THROTTLE_NUDGE works?

Thanks for taking a look.

The plane will fly at less than 100% throttle, but it’s more a question of altitude (loss). I’ll give it a try.

BTW, what’s the difference between TRIM_THROTTLE and THR_MAX? Reading Complete Parameter List — Plane documentation I’m unclear, and also not sure what “normal flight” means here:

The target percentage of throttle to apply for normal flight

What are the speeds you’re looking at? 26m/s is pretty much its max. The fwd motor is this one: http://www.hobbyking.com/hobbyking/store/uh_viewItem.asp?idProduct=56220

This is a flying wing so not the best at flying, and it’s pretty heavy – over 2kg.

Isn’t 1 the default value? I hadn’t paid attention to this parameter at all. Should I set it back to 0 and let it do its thing? What are the primary uses of throttle nudging?

Can you define “pretty crazy throttle results” ? I’ll see if that matches what I see when it’s in the air.

altitude loss is caused by it not achieving the desired speed, plus the fact that the pitch loop is not properly tuned.
Think about the energy balance. If you are flying at 18m/s and want to fly at 25m/s then the aircraft must gain kinetic energy. That energy has to come from somewhere. The throttle was already at maximum so it can’t gain any more from the engine. The only way to gain energy is to descend, trading potential energy for kinetic energy.

THE_MAX is the maximum throttle it will ever use. TRIM_THROTTLE is your estimate of what throttle will be needed to maintain the cruise speed (TRIM_ARSPD_CM). If that is 100% then it means you need full throttle to maintain cruise speed. That means the aircraft is not really viable.

throttle nudging gives a convenient way for the pilot to push the aircraft faster without having to use a GCS. Either don’t push the throttle stick up when in AUTO or disable it.

the plane was pitched down and had full throttle and was not gaining speed. That is crazy. It means the motor was not being effective. If you put the nose down and go to full throttle a plane should gain speed until it reaches its maximum possible airspeed (when drag holds it back). The speed it reached was well below the configured max airspeed and also well below the target airspeed. That means the aircraft as it was setup can never fly properly.

I think TRIM_ARSPD_CM at 1200 cm/s is too low then. And TRIM_THROTTLE could be lower.

The plane only flew for the first time a few days ago so no tuning has been done yet. I’m curious how you can tell though?

Agree with you on the physics part. But does this logic also apply in FBWA with ARSPD_USE=0? Because I also experienced the altitude loss in this configuration. In other words, in this configuration will the autopilot try to reach 25m/s?

The wing is probably too heavy, and/or the fwd motor too underpowered. It also has quite a lot of drag.

What changes or tests do you recommend me doing at this point to make progress on the alt loss issue?

because ATT.DesPitch and ATT.Pitch don’t match even when airspeed is above 15m/s and the VTOL motors are off.
It looks like the PTCH2SRV_* gains are way too low. Try this:

  • PTCH2SRV_P=1.5
  • PTCH2SRV_I=0.3

Thanks @tridge, much better results with the following parameters:

THROTTLE_NUDGE=0
TRIM_ARSPD_CM=1600 (was 1200)
TRIM_THROTTLE=80 (was 100)
PTCH2SRV_P=1.5 (was 0.6)
PTCH2SRV_I=0.3 (was 0.2)
ARSPD_FBW_MAX=20 (was 25)

The plane now “only” loses between 5 to 10 meters in altitude while transitioning, which is a ~5x improvement. See the small drop after the climb at 60m in quad.

Also it feels much better in handling and can climb at 80% throttle. It’s still flying with its nose up more than I would like. I thought the CG was too far aft but when I added 200g (more than 10% of its mass) to the front it didn’t seem to make much of a difference. ATT.Pitch and ATT.DesPitch both read 8 or 9 average on a straight and level auto flight segment. Ideally this would be 0?

Also the throttle, as depicted on the graph, seems quite “jerky”. THR_SLEWRATE is at 100, is this too high? I didn’t get a chance to try a lower value.

Interesting flight today with some issues. It was definitely on the windy side but it didn’t seem gusty, just strong steady ~7mph at ground level.

When it transitions it starts flapping in pitch and even more in roll. It can be roughly flown but it’s ugly and it loses altitude.

The controllers seem way out of whack. Is this a PTCH2SRV/RLL2SRV tuning issue? I don’t think I changed these values since the last good flight. I had to change a burned servo recently though. Flying wing elevons.

EDIT: this is arduplane 3.7.1

DF logs: https://dl.dropboxusercontent.com/u/67653/share/2016-10-23.BIN