/**
     * Constructs the AHRS class, overriding the default update rate
     * with a custom rate which may be from 4 to 60, representing
     * the number of updates per second sent by the navX MXP.  
     * 
     * Note that increasing the update rate may increase the 
     * CPU utilization.
     * @param serial_port SerialPort object to use
     * @param update_rate_hz Custom Update Rate (Hz)
     */
AHRS::AHRS(SerialPort *pport, uint8_t update_rate_hz) : IMU(pport,update_rate_hz)
{
                this->current_stream_type = MSGID_AHRS_UPDATE;
                world_linear_accel_x =
                        world_linear_accel_y =
                        world_linear_accel_z =
                        mpu_temp_c =
                        fused_heading =
                        altitude =
                        barometric_pressure =
                        baro_sensor_temp_c =
                        mag_field_norm_ratio = 0.0f;
        cal_mag_x = 
                        cal_mag_y =
                        cal_mag_z = 0;
        is_moving =
                        is_rotating =
                        altitude_valid =
                        is_magnetometer_calibrated =
                        magnetic_disturbance = false;
        ResetDisplacement();
}
InertialDataIntegrator::InertialDataIntegrator() {
    ResetDisplacement();
}