DavidGillsjo / VideoIMUCapture-Android

Android application for capture of Video, IMU data and Camera data useful in SLAM and Structure from Motion research. Differs between Optical Image Stabilization (OIS) and Digital Video Stabilization (DVS) and can provide OIS data if the device supports it.
GNU General Public License v3.0
232 stars 43 forks source link

Added magnetometer reading & but couldn't read from .pb3 #8

Closed johnnyhoichuen closed 1 year ago

johnnyhoichuen commented 1 year ago

I'm modifying the code such that it reads magnetometer data. However, when I read from the .pb3, only gyro and accel data are available. Everything including the .proto compiled successfully.

image

Here are the modified codes from IMUManager and Recording.proto:

IMUManager

public class IMUManager extends SensorEventCallback {
    private static final String TAG = "IMUManager";
    private int ACC_TYPE;
    private int GYRO_TYPE;
    private int MAG_TYPE;

    // if the accelerometer data has a timestamp within the
    // [t-x, t+x] of the gyro data at t, then the original acceleration data
    // is used instead of linear interpolation
    private final long mInterpolationTimeResolution = 500; // nanoseconds
    private final int mSensorRate = 10000; //Us, 100Hz
    private long mEstimatedSensorRate = 0; // ns
    private long mPrevTimestamp = 0; // ns
    private float[] mSensorPlacement = null;

    private static class SensorPacket {
        long timestamp;
        float[] values;

        SensorPacket(long time, float[] vals) {
            timestamp = time;
            values = vals;
        }
    }

    private static class SyncedSensorPacket {
        long timestamp;
        float[] acc_values;
        float[] gyro_values;
        float[] mag_values;

        SyncedSensorPacket(long time, float[] acc, float[] gyro, float[] mag) {
            timestamp = time;
            acc_values = acc;
            gyro_values = gyro;
            mag_values = mag;
        }
    }

    // Sensor listeners
    private SensorManager mSensorManager;
    private Sensor mAccel;
    private Sensor mGyro;
    private Sensor mMag;

    private int linear_acc; // accuracy
    private int angular_acc;
    private int mag_acc;

    private volatile boolean mRecordingInertialData = false;
    private RecordingWriter mRecordingWriter = null;
    private HandlerThread mSensorThread;

    private Deque<SensorPacket> mGyroData = new ArrayDeque<>();
    private Deque<SensorPacket> mAccelData = new ArrayDeque<>();
    private Deque<SensorPacket> mMagData = new ArrayDeque<>();

    public IMUManager(Activity activity) {
        super();
        mSensorManager = (SensorManager) activity.getSystemService(Context.SENSOR_SERVICE);
        setSensorType();
        mAccel = mSensorManager.getDefaultSensor(ACC_TYPE);
        mGyro = mSensorManager.getDefaultSensor(GYRO_TYPE);
        mMag = mSensorManager.getDefaultSensor(MAG_TYPE);
    }

    private void setSensorType() {
        if (Build.VERSION.SDK_INT >= 26)
            ACC_TYPE = Sensor.TYPE_ACCELEROMETER_UNCALIBRATED;
        else
            ACC_TYPE = Sensor.TYPE_ACCELEROMETER;
        GYRO_TYPE = Sensor.TYPE_GYROSCOPE_UNCALIBRATED;
        MAG_TYPE = Sensor.TYPE_MAGNETIC_FIELD_UNCALIBRATED;
    }

    public Boolean sensorsExist() {
        return (mAccel != null) && (mGyro != null) && (mMag != null);
    }

    public void startRecording(RecordingWriter recordingWriter) {
        mRecordingWriter = recordingWriter;
        writeMetaData();
        mRecordingInertialData = true;
    }

    public void stopRecording() {
        mRecordingInertialData = false;
    }

    @Override
    public final void onAccuracyChanged(Sensor sensor, int accuracy) {
        if (sensor.getType() == ACC_TYPE) {
            linear_acc = accuracy;
        } else if (sensor.getType() == GYRO_TYPE) {
            angular_acc = accuracy;
        } else if (sensor.getType() == MAG_TYPE) {
            mag_acc = accuracy;
        }
    }

    private SyncedSensorPacket syncInertialData() {
        // skip
    }

    private void writeData(SyncedSensorPacket packet) {
        RecordingProtos.IMUData.Builder imuBuilder =
                RecordingProtos.IMUData.newBuilder()
                        .setTimeNs(packet.timestamp)
                        .setAccelAccuracyValue(linear_acc)
                        .setGyroAccuracyValue(angular_acc)
                        .setMagAccuracyValue(mag_acc);

        for (int i = 0 ; i < 3 ; i++) {
            imuBuilder.addGyro(packet.gyro_values[i]);
            imuBuilder.addAccel(packet.acc_values[i]);
            imuBuilder.addMag(packet.mag_values[i]);
        }
        if (ACC_TYPE == Sensor.TYPE_ACCELEROMETER_UNCALIBRATED) {
            for (int i = 3 ; i < 6 ; i++) {
                imuBuilder.addAccelBias(packet.acc_values[i]);
            }
        }
        if (GYRO_TYPE == Sensor.TYPE_GYROSCOPE_UNCALIBRATED) {
            for (int i = 3 ; i < 6 ; i++) {
                imuBuilder.addGyroDrift(packet.gyro_values[i]);
            }
        }
        if (MAG_TYPE == Sensor.TYPE_MAGNETIC_FIELD_UNCALIBRATED) {
            for (int i = 3 ; i < 6 ; i++) {
                imuBuilder.addMagBias(packet.mag_values[i]);
            }
        }

        mRecordingWriter.queueData(imuBuilder.build());
    }

    private void writeMetaData() {
        RecordingProtos.IMUInfo.Builder builder = RecordingProtos.IMUInfo.newBuilder();
        if (mGyro != null) {
            builder.setGyroInfo(mGyro.toString()).setGyroResolution(mGyro.getResolution());
        }
        if (mAccel != null) {
            builder.setAccelInfo(mAccel.toString()).setAccelResolution(mAccel.getResolution());
        }
        if (mMag != null) {
            // verified mag is present
            Log.d(TAG, "writeMetaData: " + mMag.toString() + " " + mMag.getResolution());
            builder.setMagInfo(mMag.toString()).setMagResolution(mMag.getResolution());
        }
        builder.setSampleFrequency(getSensorFrequency());

        //Store translation for sensor placement in device coordinate system.
        if (mSensorPlacement != null) {
            // TODO: 19/1/2023 what is this placement??
            Log.d(TAG, "writeMetaData, mSensorPlacement: " + mSensorPlacement);

            builder.addPlacement(mSensorPlacement[3])
                    .addPlacement(mSensorPlacement[7])
                    .addPlacement(mSensorPlacement[11]); // original only up to 11
        }
        mRecordingWriter.queueData(builder.build());

        Log.d(TAG, "writeMetaData: builder.build()" + builder.build());
    }

    private void updateSensorRate(SensorEvent event) {
        long diff = event.timestamp - mPrevTimestamp;
        mEstimatedSensorRate += (diff - mEstimatedSensorRate) >> 3;
        mPrevTimestamp = event.timestamp;
    }

    public float getSensorFrequency() {
        return 1e9f/((float) mEstimatedSensorRate);
    }

    @Override
    public final void onSensorChanged(SensorEvent event) {
        if (event.sensor.getType() == ACC_TYPE) {
            SensorPacket sp = new SensorPacket(event.timestamp, event.values);
            mAccelData.add(sp);

            updateSensorRate(event);
        } else if (event.sensor.getType() == GYRO_TYPE) {
            SensorPacket sp = new SensorPacket(event.timestamp, event.values);
            mGyroData.add(sp);

            // sync data
            SyncedSensorPacket syncedData = syncInertialData();
            if (syncedData != null && mRecordingInertialData) {
                writeData(syncedData);
            }
        } else if (event.sensor.getType() == MAG_TYPE) {
            SensorPacket sp = new SensorPacket(event.timestamp, event.values);
            mMagData.add(sp);
        }
    }

    @Override
    public final void onSensorAdditionalInfo(SensorAdditionalInfo info) {
        if (mSensorPlacement != null) {
            return;
        }

        // what is this
        if ((info.sensor == mAccel) && (info.type == SensorAdditionalInfo.TYPE_SENSOR_PLACEMENT)) {
            Log.d(TAG, "onSensorAdditionalInfo: accel adding sensor placement");
            mSensorPlacement = info.floatValues;
        }
    }

    /**
     * This will register all IMU listeners
     * https://stackoverflow.com/questions/3286815/sensoreventlistener-in-separate-thread
     */
    public void register() {
        if (!sensorsExist()) {
            return;
        }
        mSensorThread = new HandlerThread("Sensor thread",
                Process.THREAD_PRIORITY_MORE_FAVORABLE);
        mSensorThread.start();
        // Blocks until looper is prepared, which is fairly quick
        Handler sensorHandler = new Handler(mSensorThread.getLooper());
        mSensorManager.registerListener(this, mAccel, mSensorRate, sensorHandler);
        mSensorManager.registerListener(this, mGyro, mSensorRate, sensorHandler);
        mSensorManager.registerListener(this, mMag, mSensorRate, sensorHandler);
    }

    /**
     * This will unregister all IMU listeners
     */
    public void unregister() {
        if (!sensorsExist()) {
            return;
        }
        mSensorManager.unregisterListener(this, mAccel);
        mSensorManager.unregisterListener(this, mGyro);
        mSensorManager.unregisterListener(this, mMag);
        mSensorManager.unregisterListener(this);
        mSensorThread.quitSafely();
        stopRecording();
    }
}

Recording.proto

syntax = "proto3";

import "google/protobuf/timestamp.proto";

package videoimu;

option java_package = "se.lth.math.videoimucapture";
option java_outer_classname = "RecordingProtos";

message CameraInfo {
  //fx, fy, cx, cy, s
  // See https://developer.android.com/reference/android/hardware/camera2/CameraCharacteristics#LENS_INTRINSIC_CALIBRATION
  // for details on how to use the intrinsics, pose_translation and pose_rotation.
  repeated float intrinsic_params = 1;
  //Radial: k1,k2,k3, Tangential: k4,k5
  repeated float distortion_params = 2;
  bool optical_image_stabilization = 3;
  bool video_stabilization = 4;
  bool distortion_correction = 10;
  int32 sensor_orientation = 14;

  enum FocusCalibration {
    UNCALIBRATED = 0;
    APPROXIMATE = 1;
    CALIBRATED = 2;
  }
  FocusCalibration focus_calibration = 5;

  enum TimestampSource {
    UNKNOWN = 0;
    REALTIME = 1;
  }
  TimestampSource timestamp_source = 6;

  enum LensPoseReference {
    PRIMARY_CAMERA = 0;
    GYROSCOPE = 1;
    UNDEFINED = 2;
  }
  LensPoseReference lens_pose_reference = 7;
  repeated float lens_pose_rotation = 8;
  repeated float lens_pose_translation = 9;

  message Size {
    int32 width = 1;
    int32 height = 2;
  }
  Size resolution = 11;
  Size pre_correction_active_array_size = 12; //SENSOR_INFO_PRE_CORRECTION_ACTIVE_ARRAY_SIZE
  repeated float original_intrinsic_params = 13;

}

message VideoFrameToTimestamp{
  int64 time_us = 1;
  int64 frame_nbr = 2;
}

message VideoFrameMetaData {
  int64 time_ns = 1;
  int64 frame_number = 2;
  int64 exposure_time_ns = 3;
  int64 frame_duration_ns = 4;
  int64 frame_readout_ns = 5;
  int32 iso = 6;
  float focal_length_mm = 7;
  float est_focal_length_pix = 8;
  float focus_distance_diopters = 9;

  message OISSample {
    int64 time_ns = 1;
    float x_shift = 2;
    float y_shift = 3;
  }
  repeated OISSample OIS_samples =10;
  bool focus_locked = 11;
}

message IMUInfo {
  string gyro_info = 1;
  float gyro_resolution = 2;
  string accel_info = 3;
  float accel_resolution = 4;
  string mag_info = 5;
  float mag_resolution = 6;

  float sample_frequency = 7; //Hz
  repeated float placement = 8;
}

message IMUData {
  int64 time_ns = 1;
  repeated float gyro = 2;
  repeated float gyro_drift = 3;
  repeated float accel = 4;
  repeated float accel_bias = 5;
  repeated float mag = 6;
  repeated float mag_bias = 7;

  enum Accuracy {
    UNRELIABLE=0;
    LOW = 1;
    MEDIUM = 2;
    HIGH = 3;
  }
  Accuracy gyro_accuracy = 8;
  Accuracy accel_accuracy = 9;
  Accuracy mag_accuracy = 10;

}

message VideoCaptureData {
  google.protobuf.Timestamp time = 1;
  CameraInfo camera_meta = 2;
  IMUInfo imu_meta = 3;

  repeated IMUData imu = 4;
  repeated VideoFrameMetaData video_meta = 5;

}

message MessageWrapper {
  oneof msg {
    CameraInfo camera_meta = 1;
    IMUData imu_data = 2;
    IMUInfo imu_meta = 3;
    VideoFrameMetaData frame_meta = 4;
    VideoFrameToTimestamp frame_time = 5;
  }
}

I further debug with the app but still have no clue. For example with the imu meta data

image

The message contains magnetometer info until it write to the file. But when I read from the file, nothing about magnetometer was there.

johnnyhoichuen commented 1 year ago

Turns out I made some mistakes in recompiling the .proto with protoc command. The above code works now

DavidGillsjo commented 1 year ago

Great! Sounds like a neat addition. Feel free to make a pull request if you find the time.