Compass module HGLRC M80 PRO M80PRO with QMC5883L chip Direction jumps

I am using a new Compass & GPS module “HGLRC M80 PRO M80PRO” with a QMC5883L chip in my airplane with ArduPilot version 4.5.1. In the parameters it is specified as “COMPASS_DEV_ID,855297”. The compass can also be seen in the graphical device overview and is specified as QMC5883L. When I turn the aircraft, the geographical direction changes at some point. I have already tried all orientations. (Roll 0, 90, 180, 270 & Pitch 0, 90, 180, 270) and combinations thereof. At some point, the direction of the compass jumps in the opposite direction.
I tried the controller with the compass under INAV and the compass works there. Each axis (x,y,z) changes its value with the corresponding movement. So each axis is communicated and the sensor is also okay.
The GPS itself works perfectly and is fairly accurate. - It is also a different protocol on a different interface.
Can anyone give me a tip on what I should do to make the compass work properly?
Here are a few more parameters:
COMPASS_AUTO_ROT,2
COMPASS_AUTODEC,1
COMPASS_CAL_FIT,16
COMPASS_DEC,0.0597929
COMPASS_DEV_ID,855297

Thank you for your support

I have once again recorded the telemetry data for each cardinal direction
North:


East:

South:

West:

I have been struggling to get my compass to line up too using plane, I think there is something not right as i tried a lot of orientations and calibrations but it just doesn’t line up with reality.

Have you tried to calibrate it at a different location? Open field, away from power lines.

Also, my own experience with QMC5883L mags has been rather poor. They’re Chinese clones of Honeywell chips (“HMC5883L”), and maybe their QC is just bad. In any case, maybe consider that it’s not your calibrating but the mag that’s causing the issues.

I don’t have lots of experience with iNav, but maybe their requirements for a successful calibration just isn’t as strict as Ardupilot’s. Or they implement the QMC better.

In any case, the two register halves for x,y,z are swapped for the two magnetic field sensors. The absolute value may also be stored in different sizes. You would have to debug or at least look at the source code.
Perhaps you can find a LUA script somewhere that outputs the three registers for XY and Z in the messages and you can possibly see any breakouts in the values. If you rotate the model in a uniform motion, you should be able to recognize a sine curve in the values. At least that’s my idea.

Have you ever looked at the online tool ArduPilot MAGFit WebTool? I have tried to calibrate my compass with it or have the parameters generated for me. Strangely enough, the COMPASS_OFS_Z (871.84894) parameter is quite large for me.
After the reboot, the message “Compass not calibrated” no longer appears. Instead the message: PreArm: Check mag field (xy diff:373>100)

My compass probably spits out values that are too high.
According to the data sheet, the gain/level of the three axes can be configured. However, the code would have to be changed for this

Which controller are you using with the QMC5883L compass? I have a solution.
I have adapted the source code very simply and divided the measured value by 4. — Now the compass can be calibrated

For the info: → libraries/AP_Compass/AP_Compass_QMC5883L.cpp
168 // orig const float range_scale = 1000.0f / 3000.0f;
169 // Jonny Test
170 const float range_scale = 1000.0f / (3000.0f * 4.0f);
171
172 buffer.rx = 0;
173 buffer.ry = 0;
174 buffer.rz = 0;
175
176 uint8_t status;