Integrating 3DM CV7 AHRS IMU with ArduCopter

I am currently working on integrating the 3DM CV7 AHRS IMU with ArduCopter. This IMU provides orientation and sensor data via serial communication (UART), and I would like to interface it with ArduCopter through the existing AP_ExternalAHRS system.

I noticed that support for the MicroStrain 3DM GQ7 and 3DM CV5/GX5 IMUs is already present in the codebase under the AP_ExternalAHRS folder (specifically AP_ExternalAHRS_MicroStrain7.cpp and AP_ExternalAHRS_MicroStrain5.cpp). These classes seem to handle communication with similar IMUs, so I would like to use them as a reference for implementing the 3DM CV7 support.

My main questions are:

  1. Do I need to create a new class for the 3DM CV7, or can I reuse existing functionality? Should I create a new class like AP_ExternalAHRS_MicroStrainCV7.cpp, or is it possible to extend the existing functionality? What would be the best approach to integrating the 3DM CV7 AHRS with ArduCopter without reinventing the wheel?
  2. Which classes should I reference in the AP_ExternalAHRS folder? I’m considering using the AP_ExternalAHRS_MicroStrain7.cpp (for the 3DM GQ7) and AP_ExternalAHRS_MicroStrain5.cpp (for the CV5/GX5) files as templates. Are these the right files to reference, or are there other classes that I should look at to handle the 3DM CV7 integration?
  3. What functions do I need to implement for the 3DM CV7? From my understanding, I will need to implement certain functions like build_packet(), post_imu(), and post_filter() to process the 3DM CV7 IMU data. Should I follow the pattern from the existing MicroStrain IMU classes? Additionally, will I need to implement the quaternion-to-Euler conversion, similar to how it’s done in the code below?
void AP_ExternalAHRS_MicroStrainCV7::get_orientation(float &roll, float &pitch, float &yaw) const {
    if (!state.have_quaternion) {
        roll = pitch = yaw = 0.0f;
        return;
    }

    const float w = state.quat.w;
    const float x = state.quat.x;
    const float y = state.quat.y;
    const float z = state.quat.z;

    roll = std::atan2(2.0f * (w * x + y * z), 1.0f - 2.0f * (x * x + y * y));
    pitch = std::asin(2.0f * (w * y - z * x));
    yaw = std::atan2(2.0f * (w * z + x * y), 1.0f - 2.0f * (y * y + z * z));

    constexpr float rad_to_deg = 180.0f / 3.14159265359f;
    roll *= rad_to_deg;
    pitch *= rad_to_deg;
    yaw *= rad_to_deg;
}

  1. How to properly integrate the 3DM CV7 IMU data into ArduCopter? Once the data is processed, I need to pass it to ArduCopter’s other systems (e.g., GPS, compass, barometer, and filter). What is the best way to ensure that the 3DM CV7 data is integrated correctly, especially within the context of ArduCopter?

ArduCopter Parameters for SITL Testing:

Additionally, for the integration to work properly during Software in the Loop (SITL) testing, I plan to set the following parameters in Mission Planner:

  • AHRS_EKF_TYPE: Set to 11 to use the External AHRS as the primary estimator.
  • EAHRS_TYPE: Set to 2 to specify the External AHRS backend.
  • SERIALx_PROTOCOL: Set to 36 for the serial port used by the AHRS (e.g., SERIAL4_PROTOCOL for Pixhawk4).
  • SERIALx_BAUD: Set this to the baud rate (e.g., 115200 for Plane, 921600 for Copter).
  • EAHRS_RATE: Set this to the rate in Hz of the fastest data from the AHRS (e.g., 50 for Plane, 500 for Copter).
  • GPS_TYPE: Set to 2 for Pixhawk GPS or 21 for LORD GPS.
  • GPS_AUTO_SWITCH: Set to 0 to prevent Ardupilot from switching between GPS systems.

Summary of My Plan:

  1. Reference AP_ExternalAHRS_MicroStrain7.cpp and AP_ExternalAHRS_MicroStrain5.cpp to understand how to interface with serial IMUs.
  2. Write a class AP_ExternalAHRS_MicroStrainCV7.cpp, implementing functions like build_packet(), post_imu(), and post_filter().
  3. Implement quaternion-to-Euler conversion to extract roll, pitch, and yaw from the 3DM CV7.
  4. Set the appropriate parameters in Mission Planner to test in SITL and integrate the 3DM CV7 with ArduCopter.

I would really appreciate any help or guidance on the best approach for integrating the 3DM CV7 AHRS IMU with ArduCopter. If anyone has already worked with similar IMUs or has suggestions on how to proceed, I’d love to hear your thoughts.