Q_plane: Pitch command changes to roll reaction and vice versa

Hi,

My work group and me experience some very curious effects using the Arduplane with Q-Plane. (V4.1.1 up to 4.2 dev)
We probably missed a configuration parameter, but after several days of testing we don’t know how to proceed.
If it helps i can try to process some log data, but i guess we just made a very basic mistake?

Directly after arming, everything works great. Takeoff in Qstabilize and Q-hover works well. Control via RC is working as it’s expected.
After some yaw inputs in flight, the problem begins:
Giving e.g. roll inputs from the RC results in a roll response, but also some pitch response.
The more RC yaw input was given, the more this effect increases: a rotation by 90degrees is pretty common.
Basically i was able to control the aircraft (connected to a safety line) by imagining the wingtip as “forward”.
One time we even made it to over 180° rotation: Basically the nose of the aircraft was looking towards me, but i was steering it as it was looking away from me.

In the beginning we thought it is due to a C+±code modification we need for our aircraft, but ground tests using the stock stable Versions result in the same effect:
Aircraft mounted in the lab without propellers in a fixed position.(Maybe this causes problems as well?)
After arming, everything works right.
After RC inputs on yaw, the roll motors react to pitch inputs and vice versa.
After a disarm and rearming this effect is reset as well.
Even going to throttle min resets this effect, although this was not tested in flight!

We did try the following:
- Different Software versions. V4.1.1, V4.1.2, v4.1.3, v4.1.4 (tested on Pixhawk 4 only), 4.2-dev modified and self-compiled.
- In flight we tested it on one Pixhawk 1, in the lab we used two Pixhawk 1 and one brand new Pixhawk 4 hardware.
- For the ground tests in the lab we tested:
○ with and without GPS. (CAN-GPS on Pixhawk 1, and standard Holybro Kit-GPS on Pixhawk 4)
○ With our parameters, set according to the manual
○ With no changes to the standard parameters other than the basic requirements (frame, Servo-settings, Q_enable)
○ Copter firmware with stock settings + necessary settings (Quad, + Frame, no safetyswitch, reduced arming warnings to arm) + Accelerometer and compass calibration → same result. As soon as some yaw input is made, the RC input is mixed to the roll and pitch motors instead of only going to the correct motors.
○ Checked that simple mode and super simple mode are deactivated

It feels a little bit like the simple mode in the Copter firmware must work, but it was never activated and i think is not even available on arduplane.
If you could show us the missed parameter or point us in a good direction what we can test, it would be greatly appreciated!

Thank you
Christian Rieger

Hi,

I wrote a detailed log analysis yesterday and today and by doing that i found a possible cause for this effect. I will write my current guess first and attach my complete analysis below anyway. Maybe this helps someone else or in case i got it wrong again. The logfile from the real flight is attached in the next post.

Current guess:

  • Assumption: The RC inputs are added/control the desired attitude frame.
  • If for any cause, the desired yaw frame has an (90°) angle in yaw towards the actual attitude, a RC input is mixed (90° → Roll to pitch, pitch to roll) during the reference frame conversion to the reals AC attitude.

This brings several effects:

  1. I found that we had diverging Yaw and desired yaw, and the angle between both describes the amount of observed rotation pretty good. This might be caused due to a bad (secondary) Compass of the Pixhawk itself, located in the EMI problematic fuselage. This might be the cause for the EKF Yaw resets we get as well.
  2. During ground tests in the lab, the air frame obviously didn’t move. But the desired yaw was changed by giving yaw inputs. This results in exactly the same effect as in flight, although this time no Compass problem needs to be involved. → ground testing is only possible in a very limited amount.
    IF this is the cause, this is a deliberate design choice. (maybe related: Des_YAW changes)
    In case of a copter, flying far away, this might be a good thing. If a gust changes the attitude, the pilot can’t see that and assumes it holded the desired position. But if the pilot still sees the aircraft well and can identify it much better (VTOL/Qplane), this design brings the Problem that the pilot does NOT expect that the steering reference frame is different to the aircraft airframe.

→ Maybe solved by deactivating the internal Compass and eliminating the EKF Yaw resets.
→ Probably an additional error was made in the PID tuning, resulting in this deviation between desired and actual yaw attitude while not actuating the tilt motors to compensate. → Resetting all parameters and only testing in real flight, not in the lab.

Additional ideas are always welcome!

Thank you
-Christian



If you are still interested in the complete log analysis:

I analyzed the logfile from our last flight.This flight was done with a self-compiled version of Ardupilot.
Our aircraft has two big Propeller in the front and back and 2 small Motors near the wingtips that are tiltable for cruise flight and yaw control.We made 2 changes in the motor AP_MotorsMatrix.cpp to accommodate for that:
Instead of the add_motors function we use the add_motors_raw function directly.

  1. This way we were able to reduce the Thrust for the roll-motors (smaller motors).To achieve that, we added a fifth factor to the add_motors_raw function that uses the already available fifth input at add_motor_raw. → works
  2. Additionally we set the yaw_factor to zero for all motors. (AP_MOTORS_MATRIX_YAW_FACTOR_CW changed to a fixed 0) Our yaw is achieved via motor tilting since the front and back motor turn in different directions with our configuration and can’t be used for yaw control. (We tried it with the original factors as well, with the same problem as described in the last post.

Now let’s look at the logs:
We filmed every flight so i was able to compare the logged data to the video.
The plane was attached to a safety line from above, so we had to stay really close to the takeoff position.During the first 2/3 of the flight i tried to only make inputs in either roll or pitch. Afterwards i just kept the plane on point and in the end stopped the motors, basically just hanging it into the safety line.

  1. RC inputs
    As you can see, the inputs for C1 (Roll) are the ones i used to give inputs. Only one time i used C2 (pitch).
    The inuts on the C2 channel are mainly to keep the aircraft within our safety cage during the test.

  2. The logged attitude is in very good accordance with the video. As you can see, the first impulses (14:46:47) are almost only roll reactions even though some small pitch inputs were given. The next impulses were pretty perfect only roll inputs, but already the (att.)roll amplitude is much lower and the pitch attitude is getting bigger amplitudes. At 14.47:30, (almost) only roll inputs are given, but the pitch attitude is changing more than the roll attitude. At 14.47:57 is the moment where a pitch input was given instead of roll. This resulted in primarily roll attitude change. (all verified with video)

  3. Now let’s have a look if the RC inputs are processed right: Is the RC_in processed to a correct desired attitude.
    This is working correctly. Roll and pitch are NOT mixed up here. The big oscillations in the end are when the plane was disarmed and swinging on the safety rope.


  4. Correlation between desired roll and attitude_roll
    This correlation is getting worse with time during the flight.

    The correlation for pitch is bad overall, but getting worse with time as well.

  5. For a complete view, here is the Yaw input and desired yaw. We found that giving yaw inputs accelerates this problem a lot.

    I am also not sure why the desired yaw and attitude Yaw are so much apart. Might this be the problem? Is the coordinate system for steering fixed to the desired Yaw position and not to the actual Yaw position?After disarming, both values converge again.Picture 08

  6. Correlation between RC input roll and ESC-PWM for one roll motor
    The Problem is visible again

    Even worse, for RC input pitch and ESC-PWM of a pitching motor:

    Pictures for both ESC outputs as well as Roll in or pitch in can be found below.

  7. Vibrations seem to be in an acceptable range. This flight regime shows the time with most vibrations during flight due to all motors turning. As soon as all debugging and setting is performed the damping of the Pixhawk as well as better connection of the cables is still possible.

  8. Innovations of the GPS seem to be ok. The value is in range, but some are a little off-center. The GPS accuracy is good.

  9. Same with the magnetometer. Power lines are positioned quite close to the sensor (<10A ~5cm away) and we were only able to make a large vehicle calibration. Picture 22

  10. XKF1 roll angles vs Roll input

    and vs pitch input

Additional graphs:








Downloadlink to the logfile itself:
https://gigamove.rwth-aachen.de/en/download/3d8610d8bf4c7089f45d362da10b11a2

Ok. We finally made a test flight with the internal Pixhawk Compass deactivated and all PIDs returned to factory values…

And it works!!!

The desired Yaw and actual Yaw are pretty well aligned with only small oszillations. (-> tuning needed)

We only have to look if going over the recommended max. Yaw P and D gains is advisable. After only a few tests we are at max with both parameters already.

More tuning will be done after the holidays.

A big thanks to all the cleanup in the AP_MotorsMatrix.cpp. (V4.1.5) Looks much cleaner and is way easier to modify! Great job!

Have great holidays and a happy new year!

-Christian

Hello, Christian!

I have exactly the same issue trying to launch a HIL simulation with Pixhawk 4.
How did you deactivated internal compass? COMPASS_USE didn’t help me unfortunately

Update:
I have disabled internal compass by commenting corresponding line in hwdef.dat but it didn’t solve the problem…

Regards, Victor

i think the main factor was the YAW PID.
Basically the real aircraft frame was moving away from the traget frame and the pilot is steering the target frame.
We just unclicked the internal compass in the missionplanner setup page.
We had another external compass!!!

Hello, Christian!

Thank you for sharing information!

Disabling compass in MP didn’t help, and in hwdef.dat also.

Finally I was managed to figure it out. My experiments like yours, also confirms that control stiks act with respect to target frame. And body frame could be much away from target frame. Probably this behaviour is ok for copters, but not very intuitive in quadplanes.

There is another thing in copter algorithms, which drags desired yaw towards the actual yaw so the difference can’t be more than 10 degrees if plane gets rotated by external forces from it’s desired yaw. And with the 10 deg difference, the effect is not noticeable (almost).

The thing with PID is that Q_A_ANG_YAW_P parameter have effect on that 10 deg limit. If parameter is set to 12 it is 10 deg, if parameter is set to 1, it is more than 100 deg.

At first I felt like I needed low values for Q_A_ANG_YAW_P but after I faced that issue, I set it to 12 and lowered Q_A_RAT_YAW_P to stabilize yaw.

1 Like