Rover without Magnetic Compass

Hi,
I tried to use my skid steer rover on top of re-enforced concrete. But there seems to be significant interference with the compass which leads to problems with navigation.

I was wondering if it is possible to run a rover without a compass in AUTO mode?

I read somewhere that it’s supposed to work for planes. But I couldn’t find any information if it is supported for rovers. In think it should be possible to use the GPS heading instead of the compass, as long as there is no side slip (drifting) of the rover. I gave it a quick try, but I constantly get a ‘BAD AHRS’ message when the compass is disabled.

Cheers,
Daniel

Yes, this has come up a few times recently and I’ve suffered from it myself. The short-term advice is to increase the value of the EK2_YAW_M_NOISE parameter to 0.7 to reduce the influence of the compass on the heading. As a reference this is what the AION robotics guys have done in their parameter file.

It is theoretically possible to run without a compass but it isn’t something I’ve tested or sorted out with our EKF expert Paul Riseborough. It’s also possible we could use a forward facing optical flow sensor. We have some code in development to allow that but not quite ready.

I think in the short-term the soluiton is the param fix mentioned above and raising the compass up higher.

txs for the report.

1 Like

Thanks for the Info! I will give EK2_YAW_M_NOISE a try once the weather here is nice again. Even though I am not sure if it will solve my issues as it still relies on the compass as the single source of absolute heading.
Similarly I am not convinced the forward facing optical flow sensor will fix the issue as optical flow can only do relative but not absolut measurements.

I spend some more time looking into the GPS heading. It looks promising. I was able to run an auto mission without a compass but it required a few hacks.

  • EKF2/3 seems to ignore the GPS heading. I think fusing the GPS heading is done when fusing the airspeed sensor. This makes sense for planes but doesn’t work for rovers as an airspeed sensor wouldn’t really work.
  • DCM supports fusing GPS headings out of the box. I had to force using DCM with AHRS_EKF_TYPE=0. Otherwise ardupilot would switch to the incorrectly initialized EKF while reversing. This strange behavoir is triggered by clearing the fly_forward flag when reversing.
  • I had to reduce the GPS_SPEED_MIN in the DCM code as my rover cannot reach 3 m/s.
  • I had to disable some checks to allow enabling AUTO mode without a valid EKF.
  • I had to disable a check for ahrs.home_is_set() in commands_logic.cpp, otherwise the rover would stop at the first waypoint.

@rmackay9, do you know if AUTO mode should work with DCM? Or if it’s intended to not work by design.

1 Like

Daniel,

Nice investigation. I’m not a fan of DCM because it doesn’t support many new functions we have including wheel encoders, external position estimates, etc. So it’s very limited compared to what the EKF is capable of.

I think we should ask @priseborough to have a look at why the EKF2/3 isn’t using the GPS heading. That surprises me!

I’ve looked at EKF2 and If the_ahrs->get_vehicle_class() == AHRS_VEHICLE_GROUND, the assume_zero_sideslip() function will always return false and alignment of yaw to GPs will never happen. The note in the code says:

// we don't assume zero sideslip for ground vehicles as EKF could
// be quite sensitive to a rapid spin of the ground vehicle if
// traction is lost

From memory was due to issues with skid to turn vehicles rapidly accelerating. We should revisit this limitation.

The other piece of logic preventing it is that it will only trigger if the plane in flight detection has been triggered, which in the absence of airspeed requires a height increase of 10m after arming.

I will check EKF3 later.

Edit: The same limitation applies to EKF3.

1 Like

I think the following modifications are required for GPS yaw alignment to work for rovers:

  1. modify the assume_zero_sideslip() function so that it removes the _ahrs->get_vehicle_class() != AHRS_VEHICLE_GROUND check
  2. Modify the inFlight status check so that that there is a ground vehicle specific case
  3. Modify the GPS speed threshold in the realignYawGPS() function so that for rovers rather than a fixed value of 5 m/s, it uses a ratio of the GPS speed to GPS speed accuracy.
1 Like

I’ve submitted some EKF changes here: https://github.com/ArduPilot/ardupilot/pull/8155

Thanks for having a look. I think I am still missing something here, so lets take a step back.

There are two diffent mechanisims to use the GPS heaing as a yaw source.

  • Occasianally reset the yaw angle to the current GPS heading. This should be done after start (when we know there no good yaw estimate yet) or when we detect the yaw estimate is bad.
  • Use the GPS heading to continously correct the yaw angle. Basically fusing the the GPS heading with the other sensors.

I believe for the EKF the first part is done in the ‘realignYawGPS’ function in PosVelFusion. This part is clear. But I cannot find where the second part is implemented (continous fusing of GPS heading). The DCM does it in the ‘drift_correction_yaw’ function.

@rmackay9 I totally agree that the EKF is superior to the DCM in many ways and that this ‘feature’ should be working with the EKF. But its also good to have a backup, that’s why I was wondering if it should be possible to use the DCM with auto mode.

nice understanding of the EKF and DCM. very few people are able to look into these parts of the system.

There is another good reason to use the DCM as a backup which is that when it loses GPS lock, it’s position estimate degrades much more slowly (I think it’s because it doesn’t ever make use of accelerometer data). Still, for me, the problem with trying to continue supporting the DCM is it greatly increases the effort we must spend on development and testing and it is so dated that it holds us back. I would personally much rather focus our limited resources on making the EKF as good as it can be.

1 Like

Hi Daniel

I am running into the same problem and am thinking of doing something similar by using GPS heading. I am interested to hear about your progress!

And for the meantime… What were the hacks that you used to run in AUTO w/o the compass?

Thanks!

There are two solutions for this:

  • Use the DCM. It basically already supports ‘compass-less’, but needs some modifications to be used in AUTO mode. The source code modifications required are listed in this post Rover without Magnetic Compass (further up in this thread).
  • The other option is to use the GPS heading in EKF2/3. This should be the preferred option and I successfully tested it. But I didn’t have the time yet to put it all into a pull request.
    This requires two parts to work properly:
    • Re-setting the current YAW to the compass course. This should happen after boot or if there is a big misalignment. There is an open pull request for this, but it needs a bit more work: https://github.com/ArduPilot/ardupilot/pull/8155.
    • Constantly fuse the GPS heading in the EKF filer. This is more work as it requires some refactoring (or hacking) in the EKF core.

If you need a quick and dirty solution, give the DCM a try.

Thanks so much Daniel!

We will give these a try!