Linux boards and compass

Heads up for those using Linux boards with HMC5883L sensor.

I merged a long standing pending PR this week that from what I can see will not affect other people: https://github.com/ArduPilot/ardupilot/pull/3792. However, please please be careful and double check the compass orientation in your board still makes sense. Particularly if it’s an internal compass. If you have an external compass, you may benefit from a new constructor now that allows the compass to be forced as external. This allows users not to have to set the compass as external via a param in GCS.

@staroselskii @mirkix @julienberaud @pritamghanghas

Hi @lucasdemarchi,

after calibrate the internal compass with Erle-Brain 2 and PXFmini works well for me.

But external compass don’t work without these changes:

AP_Compass_HMC5843.cpp

#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
      CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI

      raw_field.rotate(ROTATION_ROLL_180);
   #endif

And AP_Compass.cpp

#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
      CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI

       AP_Compass_Backend *backend = AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR));
    if (backend) {
        _add_backend(backend);
    } else {
        _add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0));
    }

Regards,

@LanderU

@LanderU why do you need to change AP_Compass.cpp to conditionally add the compass?

I think the additional rotation is needed probably because we are now doing a ROTATION_YAW_90 before the call to rotate_field() which, for external compasses will to the MAG_BOARD_ORIENTATION rotation plus the user selectable rotation.

Without the code context to your change in AP_Compass_HMC5843.cpp I’m not sure what would be the value, but you should probably set the rotation for external compasses via a param, and that will depend on how you orient your external compass.

@guludo could you double check what I said above?

Hi @lucasdemarchi,

Yes, but sometimes don’t work correctly and prefer set the rotation via code.

Regards,

@LanderU

ok. Now we want to make it work correctly, always and for all boards. Just pushed an additional patch for you in AP_Compass: simplify optional backends by lucasdemarchi · Pull Request #4121 · ArduPilot/ardupilot · GitHub

@guludo Maybe the difference in rotation is actually because we changed the place in which we are applying the rotation.

@lucasdemarchi That’s probably it. The rotation was moved so that the user selectable orientation could be with respect to the “arrow” that appears on the compass+gps kit. The idea is that the user wouldn’t need to set additional orientation if the kit is aligned with the board orientation.

I believe so. But I still think the change in the order is the right way to go for now.

But the arrow only sets 2 dimensions. For example, the user still needs to set a roll_180 for example