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
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.
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();
}
}
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.
Here are the modified codes from IMUManager and Recording.proto:
IMUManager
Recording.proto
I further debug with the app but still have no clue. For example with the imu meta data
The message contains magnetometer info until it write to the file. But when I read from the file, nothing about magnetometer was there.