Quadcopter is nearly uncontrollable

I would appreciate some help with a copter that is, by appearances, not responding to the controls well.

Outline of the problematic flights:
-arm in altitude hold mode, no errors
-as soon as I throttle up (I have PILOT_THR_BHV=1 because my stick is spring loaded) the drone rapidly ascends. I don’t know if it will stop on it’s own because I have always intervened.
-altitude hold is woefully unstable but for some reason stops around 50 meters AGL (the exact altitude is inconsistent). I switch to loiter. Loiter is better, but still bad. Throttle doesn’t obviously affect the drone, and RPY aren’t working correctly either. RPY did maintain some control, though.
-I took the first opportunity to get it to the ground to avoid a fly-away. In log 5, this occurred in loiter. In log 6, this occurred after switching to stabilize (which, frankly, I am very bad at, but it still wasn’t working how I expected).

Oddly, no compass variations or EKF errors wear thrown. I calibrated the compass, accel, and radio. I followed the setup instructions for the herelink. My motor order is correct to my knowledge (tested with mission planner’s motor test).

Autopilot: cube orange+
Radio: herelink
Firmware: ardupilot 4.5.6 (custom build that has been tested on other drones and is known to be good)
GCS: qgroundcontrol, I don’t have the version at the moment (also custom build)
Motors: droneCAN
GPS/Compass: Here4

Log 5 was first.
Log 6 was second. The main difference is PILOT_THR_BHV=1, IMU_POS=…, GPS_POS=… . I had a GCS failsafe trigger in this one, and this flight spent a decent amount of time in RTL before I switched to stabilize flight mode.

I have reviewed both log files and spent some time on this, so if you want to know what I’ve looked at, then ask away.

00000006.BIN (5.8 MB)

00000005.BIN (4.1 MB)

Another detail: I have not run autotune on this design, yet. It’s hard to do when you can’t hover. I am personally skeptical that this is the problem, and if it is, then I’m not sure how I would fix it when you can’t hover…

The motor outputs are oscillating badly, and there’s small high-frequency attitude oscillations.

Without knowing more about your copters construction and components, I would change these parameters first:

ARMING_CHECK,1
ATC_ANG_PIT_P,7
ATC_ANG_RLL_P,8
ATC_RAT_PIT_D,0.006
ATC_RAT_PIT_I,0.12
ATC_RAT_PIT_P,0.12
ATC_RAT_RLL_D,0.006
ATC_RAT_RLL_I,0.12
ATC_RAT_RLL_P,0.12
ATC_RAT_YAW_I,0.05
ATC_RAT_YAW_P,0.5
INS_ACCEL_FILTER,10
INS_HNTCH_HMNCS,1
INS_HNTCH_OPTS,2
INS_LOG_BAT_OPT,4
LOG_BITMASK,180222
PSC_ACCZ_I,0.6
PSC_ACCZ_P,0.3
PSC_VELXY_D,0.25

Since you are not using MissionPlanner and the Initial Parameters section, I’ll provide some more parameters you should use:

ATC_RAT_PIT_FLTD,15
ATC_RAT_PIT_FLTT,15
ATC_RAT_RLL_FLTD,15
ATC_RAT_RLL_FLTT,15
ATC_RAT_YAW_FLTE,2
ATC_RAT_YAW_FLTT,15

Also try MOT_SPIN_MIN,0.13

A lot of these parameter changes are fairly standard, some are chosen based on your log. Some, like the harmonic notch filter changes, are to get back to a safe / known-good place and we can work from there.

Now do another test flight in AltHold. Listen for a mechanical sound from the motors, land within 1 minute and check motor temperature. If motors are hot, or there is an odd noise, reduce ATC_RAT_PIT_D and ATC_RAT_RLL_D to 0.004 and test again.
If flight is stable and the copter behaves as commanded, try using Loiter too.
Send the .bin log file from that flight.

Please tell us more about the components: props, motors, ESCs, battery, takeoff weight.

I will try adjusting the PID parameters as you suggested. Poor weather is preventing me from flying today, though.

Props: tmotor MS1101

Motors/ESC: Vertiq 40-06, communicating with DroneCAN (integrated ESC)

Battery: 8000 mAh LiIon

Takeoff weight: 2 kg

I noticed that ESC indices 0 and 1 are reporting negative RPMs. This issue is with the same ardupilot version we’re using, and they thought it was a problem. Since I can’t easily update the firmware, is it safe to just use INS_HNTCH_MODE=0, 1, or 4? I presume the FFT has a substantial compute demand, but PM.load is maxed out at about 44% in log 6.

I’ll work on this for you - there is a setting.
Dont use FFT.

EDIT:

Use exactly these battery settings for 4 cell LiIon. Yell out if your battery is not standard LiIon, but I think it is from the battery data in the log.

BATT_ARM_VOLT,12.70
BATT_CRT_VOLT,12.00
BATT_LOW_VOLT,12.40
MOT_BAT_VOLT_MAX,16.40
MOT_BAT_VOLT_MIN,11.20

Use this to ignore those RPM drop-outs:
INS_HNTCH_OPTS,34

And change to this for 11 inch props:
MOT_THST_EXPO,0.61
The other related parameters will be close enough for now.
The MissionPlanner Initial Parameters section does all this stuff for you.

I heard back from the motor/esc manufacturer, and I can change settings on the ESC to report only positive values (speed vs velocity).

I will be testing much of this today.

This is issue is resolved. Thankyou, everyone here and elsewhere, for the help! For those that come after…

There were three symptoms that needed explained:

  1. the drone launched into the air as soon as throttle was raised above the arming region.

  2. the drone suffered from poor control and poor stability once in the air.

  3. even in stabilize flight mode, the throttle was extremely touchy. Only the bottom region of it was viable. This wasn’t entirely surprising because the power to weight ratio of this drone is over 4, although it still wasn’t working quite right.

This is what I did to fix it:

Change the notch filter settings:
INS_HNTCH_MODE=3 (was 3, verified it does NOT nullify the other settings)
INS_HNTCH_FREQ=133 (blade passing frequency for 4000 RPM with 2 blades, was 45)
INS_HNTCH_BW=66 (recommended in mission planner to be 50% the base frequency, was 25)
INS_HNTCH_OPTS=19 (double, multisource, and triple notch; was 18, multisource and triple notch)

Note:
INS_HNTCH_HMNCS enabled harmonics 1-3 (not changed)

PID gains:
—implemented—
ATC_ANG_PIT_P=7 (was 14.2514)
ATC_ANG_RLL_P=8 (was 16.2386)
ATC_ANG_YAW_P is unchanged
ATC_RAT_YAW_I,0.05
ATC_RAT_YAW_P,0.5
PSC_ACCZ_I=0.6 (was 0.7)
PSC_ACCZ_P=0.3 (was 0.35)
PSC_VELXY_D=0.25 (was 0.5)
—recommended but not implemented due to being close to existing values—
ATC_RAT_PIT_D=0.006
ATC_RAT_PIT_I=0.12
ATC_RAT_PIT_P=0.12
ATC_RAT_RLL_D,0.006
ATC_RAT_RLL_I,0.12
ATC_RAT_RLL_P,0.12

Logging:
INS_LOG_BAT_OPT=4 (was 3, enables logging of INS data before AND after the filter)
LOG_BITMASK=2238462 (enabled fast harmonic notch logging, disabled optical flow)

Motor thrust:
MOT_THST_HOVER=0.12
MOT_SPIN_MIN=0.1
MOT_SPIN_ARM=0.075

In the ESC configuration software:
Max volts=16.4 (was 25.6)
Report telemetry as speed = enabled (this means that all RPM values are positive regardless of direction)
Note: arming throttle max is 0.075

Why did that work? It’s complicated, since multiple problems were interacting with each other.

Problem #1, fundamentally, was an interaction between MOT_THST_HOVER being too high (thanks VexAzomi on discord) and the motor ESCs being configured to expect a 6 cell battery. MOT_THST_HOVER was set to 0.3, but in reality is 0.2. After arming, the throttle is raised and an ascent is commanded. Two things happen. First, the autopilot commands more thrust than expected in the first few iterations of the feedback loops due to MOT_THST_HOVER being 50% higher than it should be. This would be compensated for, but with other problems present it got out of hand. Secondly, the autopilot communicates to the ESCs (using droneCAN) to give x% of throttle. The ESCs, in voltage control mode, attempt to reach y% of voltage across the coils using y=f(x) internally. Part of y=f(x) is a converting the normalized throttle input to an actual voltage input. Because it was configured to use 25.6V, it was trying to get y% of 25.6V. This meant it there was something like a 1.56 factor more thrust obtained than what was expected by the autopilot, and it would saturate at something like 64% throttle. This, coupled with the MOT_THST_HOVER issue, caused it to absolutely launch into the sky the instant throttle went from ~10% to over 50% as it transitioned from the arming state to trying to hover.

Problem #2 likely rooted in accelerometer noise. Look back at log 6 - the accel data is noisy, even though VIBE is well within the recommended range. I compared that log with logs of another design that flies well and confirmed that the correlation between VIBE and peak to peak IMU.accz noise wasn’t straightforward. This was made a lot worse because the motors that reported a negative RPM in the esc telemetry caused the notch frequencies to be clamped low (visible in the NTF log entries). These frequencies were far below the blade pass frequency of the props at hover, causing the filter to be ineffective. This is very bad - degradation of any of the IMU’s data directly degrades the drone’s stability. Even worse, accel data is required in every flight mode I used. This probably made problem #1 even worse. This was addressed by configuring the ESCs to only output positive numbers (speed vs velocity) and setting INS_HNTCH_MODE parameters. Some work could be done on this, but the settings shown here worked pretty well.

Problem #3 is essentially the same core issues as #1, but manifesting differently. The main issue here was the scaling of the thrust output due to the ESCs being configured to a higher voltage.

Lastly, the PID parameters I changed might not have been necessary. I don’t think they caused any of the problem. However, slowing down the drone’s response (especially PSC) gives the human pilot more time to intervene and will somewhat dampen high frequency feedback from noisy sensors. I think it is a good idea to make these very slow on a new design unless you’re an ace pilot.

I believe the harmonic notch filter settings will be surplus to requirements - more is not better.
For example there is no need to have both double and triple notches, in fact it is counter productive and I think the software overrides the double setting if you use the triple setting.
Excessive notch filter aggressiveness (too many notches for example) causes lag to PIDs which can effect attitude control and response to disturbances.
You wont need fast harmonic notch logging except maybe for initial testing and configuration - dont leave that setting in place for normal use.

Please provide a log file and we might be able to simplify a few things.

Here’s the log. It’s too big for attaching to the post. Understood in regards to logging settings.

My observations:

  • FTN[0].nf1-3 are stuck at INS_HNTCH_FREQ. I checked the FFT of the accel and gyro data using mission planner. The harmonics are at 92, 175, and roughly 300 Hz, which is the rotational frequency, not the blade pass frequency. Thus, my INS_HNTCH_FREQ was wrong and should be updated (I’m not surprised). I suspect the 3rd harmonic probably doesn’t need a filter due to its relatively low magnitude.

  • I observed a drift in yaw during flight. The log indicates it is about -5 deg/s. This is my current biggest problem. Last time I experienced this on a different design, the controller’s joystick had just drifted out of calibration. I’m not sure RCIN.ch4 (yaw) supports that this time.

  • The overall noise in IMU[0].accz and vibe[0].vibez are higher than I’d prefer (I’ve done better), but I understand that may need hardware work.

According to mission planner’s description of INS_HNTCH_OPTS, “if both double and triple notches are specified only double notches will take effect.”

I looked further into the drifting yaw behavior. Att.yaw and Att.desyaw are very close (within a few tenths at most), indicating this is not a commanded behavior. IMU[0].gyrz is consistently averaging -0.1 while yaw is drifting at hover. I am guessing that this is a bad gyro calibration, and that’s all?

Harmonic Notch Filter
First up: the primary noise generated by motors and props is 92Hz. The next major harmonic is around 170Hz. It’s typical for the 2nd harmonic to have a higher amplitude that the 1st.

The trouble with all the options and notches is you get all these phase changes which affect PIDs and stability. Phase changes we are concerned about are where this red line crosses the zero mark. Ideally the red line would always be below zero. This is using the (newer) web-based filter review tool. ArduPilot Filter Review

Some of the setting you have mean the notch filter is not even working properly anyway. For example the frequency set at 133Hz.
The RPM-based notch starts at the frequency and bandwidth you nominate and will not go below that. So if you set it too high the notch never gets a chance to work. The frequency needs to be set below where noise starts and the notch filter and bandwidth are scaled up with the RPM.
For per-motor notches the bandwidth should be a quarter of the frequency as a starting point.

These are the settings you are looking for:

For this result:

In fact the INS_HNTCH_ATT can go as low as 10 and noise is still completely filtered and phase effects are further reduced. Less is more for the harmonic notch filter. Try 20 or 30 instead of 40.

Noise below about 50db, or 0.05 on the amplitude scale, does not need filtering or you just introduce more issues than you solve.
Also you can see in that graph the Gyro low-pass filter INS_GYRO_FILTER,30 is already doing a great job of filtering out the noise peaks visible above 150Hz and no further treatment is required.

Instead of a whole procession of phase changes there is now just this:

Compass calibration can be better and may be something that is affecting your yaw.
Load this file using the MissionPlanner full parameter list Compare feature. After this you should not do a compass calibration again, or these good settings will be over-written. After this you can also enable the onboard compass since the calibration will be quite usable.
MAGFit-JM.param (600 Bytes)

In the log, attitude control is quite reasonable.
Altitude control looks good.

Yaw
There are two distinct groups of motor outputs, and in this case it aligns to the clockwise and counter-clockwise motors. Therefore not a weight imbalance but a twisted arm or motor mount.
Improve the motor mount alignment (along with the compass calibration settings provided) and I’d say the yaw issue will be solved.

Set these:

FFT_ENABLE,0
INS_ACCEL_FILTER,10
LOG_BITMASK,180222

I’m unsure why you’ve changed INS_FAST_SAMPLE from default, it can probably be put back.

Run Autotune on pitch and roll after you’ve implemented all these fixes. It is unlikely yaw will need any further special treatment. Yaw is less critical and easy to fix manually anyway.

If everything is going Ok try these for Loiter, they should suit the size of your copter:

LOIT_ACC_MAX,600
LOIT_ANG_MAX,30
LOIT_BRK_ACCEL,200
LOIT_BRK_DELAY,0.3
LOIT_BRK_JERK,300

After that, do a flight with plenty of manual yaw in AltHold mode to gather data and we can adjust:
ATC_SLEW_YAW (likely to be about 30 for smooth missions)
PILOT_Y_RATE (likely to be about 60)
and you could try PILOT_Y_EXPO,0.3 for fine control near the centre of the yaw stick.

That should keep you off the streets for a while :slight_smile: