Skip to content

Commit

Permalink
Merge pull request #25 from MobileRoboticsSkoltech/sensor_additional
Browse files Browse the repository at this point in the history
Add magnetometer recording; Update sensor management logic
  • Loading branch information
anastasiia-kornilova authored Mar 24, 2021
2 parents a09afd2 + 8a5cbf6 commit dc04b0e
Show file tree
Hide file tree
Showing 19 changed files with 429 additions and 183 deletions.
8 changes: 5 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

[![Build Status](https://travis-ci.org/MobileRoboticsSkoltech/OpenCamera-Sensors.svg?branch=master)](https://travis-ci.org/MobileRoboticsSkoltech/OpenCamera-Sensors)

OpenCamera Sensors is an Android application for synchronized recording of video and IMU data. It records sensor data (accelerometer, gyroscope, magnetometer) and video with frame timestamps synced to the same clock.

## Install

[Get latest apk](https://github.com/MobileRoboticsSkoltech/OpenCamera-Sensors/releases/latest/download/app-release.apk)
Expand All @@ -13,7 +15,6 @@ OpenCamera Sensors is an Android application for synchronized recording of video

This project is based on [Open Camera](https://opencamera.org.uk/) — a popular open-source camera application with flexibility in camera parameters settings, actively supported by the community. By regular merging of Open Camera updates our app will adapt to new smartphones and APIs — this is an advantage over the other video + IMU recording applications built from scratch for Camera2API.


## Usage

![screenshot settings](https://imgur.com/BytzCvA.png)
Expand All @@ -25,10 +26,11 @@ This project is based on [Open Camera](https://opencamera.org.uk/) — a popul
- **Record video**
- **Get data** from ```DCIM/OpenCamera```:
- Video file
- IMU data and frame timestamps in the directory ```{VIDEO_DATE}```:
- Sensor data and frame timestamps in the directory ```{VIDEO_DATE}```:
-```{VIDEO_NAME}_gyro.csv```, data format: ```X-data, Y-data, Z-data, timestamp (ns)```
- ```{VIDEO_NAME}_accel.csv```, data format: ```X-data, Y-data, Z-data, timestamp (ns)```
- ```{VIDEO_NAME}_timestamps.csv```, data format: ```timestamp (ns)```
- ```{VIDEO_NAME}_magnetic.csv```, data format: ```X-data, Y-data, Z-data, timestamp (ns)```
- ```{VIDEO_NAME}_timestamps.csv```, data format: ```timestamp (ns)```

### Remote recording

Expand Down
13 changes: 6 additions & 7 deletions api_client/basic_example.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
import time
from src.RemoteControl import RemoteControl
import subprocess

HOST = '192.168.1.100' # The smartphone's IP address
HOST = '192.168.1.75' # The smartphone's IP address


def main():
Expand All @@ -11,16 +10,16 @@ def main():
remote = RemoteControl(HOST)
print("Connected")

accel_data, gyro_data = remote.get_imu(10000, True, False)
print("Accelerometer data length: %d" % len(accel_data))
with open("accel.csv", "w+") as accel:
accel.writelines(accel_data)
accel_data, gyro_data, magnetic_data = remote.get_imu(10000, True, False, True)
print("Magnetometer data length: %d" % len(magnetic_data))
with open("magnetic.csv", "w+") as imu_file:
imu_file.writelines(magnetic_data)

phase, duration = remote.start_video()
print("%d %f" % (phase, duration))
time.sleep(5)
remote.stop_video()

# receives last video (blocks until received)
start = time.time()
filename = remote.get_video(want_progress_bar=True)
Expand Down
20 changes: 13 additions & 7 deletions api_client/src/RemoteControl.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@
BUFFER_SIZE = 4096
PROPS_PATH = '../app/src/main/assets/server_config.properties'
SUPPORTED_SERVER_VERSIONS = [
'v.0.0'
'v.0.1'
]

NUM_SENSORS = 3

class RemoteControl:
"""
Expand All @@ -26,24 +26,27 @@ def __init__(self, hostname):
self.socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.socket.connect((hostname, int(self.props['RPC_PORT'])))

def get_imu(self, duration_ms, want_accel, want_gyro):
def get_imu(self, duration_ms, want_accel, want_gyro, want_magnetic):
"""
Request IMU data recording
:param duration_ms: (int) duration in milliseconds
:param want_accel: (boolean) request accelerometer recording
:param want_gyro: (boolean) request gyroscope recording
:return: Tuple (accel_data, gyro_data) - csv data strings
:param want_gyro: (boolean) request magnetometer recording
:return: Tuple (accel_data, gyro_data, magnetic_data) - csv data strings
If one of the sensors wasn't requested, the corresponding data is None
"""
accel = int(want_accel)
gyro = int(want_gyro)
magnetic = int(want_magnetic)
status, socket_file = self._send_and_get_response_status(
'imu?duration=%d&accel=%d&gyro=%d\n' % (duration_ms, accel, gyro)
'imu?duration=%d&accel=%d&gyro=%d&magnetic=%d\n' % (duration_ms, accel, gyro, magnetic)
)
accel_data = None
gyro_data = None
magnetic_data = None

for i in range(2):
for i in range(NUM_SENSORS):
# read filename or end marker
line = socket_file.readline()
msg = line.strip('\n')
Expand All @@ -62,8 +65,11 @@ def get_imu(self, duration_ms, want_accel, want_gyro):
accel_data = data
elif msg.endswith("gyro.csv"):
gyro_data = data
elif msg.endswith("magnetic.csv"):
magnetic_data = data

socket_file.close()
return accel_data, gyro_data
return accel_data, gyro_data, magnetic_data

def start_video(self):
"""
Expand Down
1 change: 1 addition & 0 deletions app/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ android {
defaultConfig {
applicationId "com.opencamera_extended.app"
minSdkVersion 19
// Important! When we decide to change this to 30 or more, we need to add full support for scoped storage
targetSdkVersion 29

renderscriptTargetApi 21
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
import java.util.HashSet;
import java.util.List;
import java.util.Locale;
import java.util.Map;
import java.util.Set;

import net.sourceforge.opencamera.LocationSupplier;
Expand All @@ -31,6 +32,7 @@
import net.sourceforge.opencamera.SaveLocationHistory;
import net.sourceforge.opencamera.cameracontroller.CameraController;
import net.sourceforge.opencamera.preview.Preview;
import net.sourceforge.opencamera.sensorlogging.RawSensorInfo;
import net.sourceforge.opencamera.ui.FolderChooserDialog;
import net.sourceforge.opencamera.ui.PopupView;

Expand All @@ -47,6 +49,7 @@
import android.graphics.Matrix;
import android.graphics.Point;
import android.graphics.PointF;
import android.hardware.Sensor;
import android.hardware.camera2.CameraMetadata;
import android.hardware.camera2.CaptureRequest;
import android.hardware.camera2.params.TonemapCurve;
Expand Down Expand Up @@ -7838,6 +7841,64 @@ public void testVideoImuInfo() throws InterruptedException {
assertEquals(expectedNFiles + 1, nNewFiles);
}

/* Test recording video with all sensors enabled
Assumes all of the sensors are supported
*/
public void testVideoAllSensors() throws InterruptedException {
Log.d(TAG, "testVideoAllSensors");
// check sensor files
Map<Integer, File> sensorFilesMap = subTestVideoSensors(true, true, true);
assertSensorRecFileExists(Sensor.TYPE_GYROSCOPE, sensorFilesMap);
assertSensorRecFileExists(Sensor.TYPE_MAGNETIC_FIELD, sensorFilesMap);
assertSensorRecFileExists(Sensor.TYPE_ACCELEROMETER, sensorFilesMap);
}

public void testVideoMagnetometer() throws InterruptedException {
Log.d(TAG, "testVideoMagnetometer");
Map<Integer, File> sensorFilesMap = subTestVideoSensors(true, false, false);
assertSensorRecFileExists(Sensor.TYPE_MAGNETIC_FIELD, sensorFilesMap);
}

public void testVideoAccel() throws InterruptedException {
Log.d(TAG, "testVideoAccel");
Map<Integer, File> sensorFilesMap = subTestVideoSensors(false, true, false);
assertSensorRecFileExists(Sensor.TYPE_ACCELEROMETER, sensorFilesMap);
}

public void testVideoGyro() throws InterruptedException {
Log.d(TAG, "testVideoGyro");
Map<Integer, File> sensorFilesMap = subTestVideoSensors(false, false, true);
assertSensorRecFileExists(Sensor.TYPE_GYROSCOPE, sensorFilesMap);
}

private void assertSensorRecFileExists(Integer sensorType, Map<Integer, File> sensorFilesMap) {
assertTrue(
mActivity.getRawSensorInfoManager().isSensorAvailable(sensorType) &&
sensorFilesMap.get(sensorType).canRead()
);
}

public Map<Integer, File> subTestVideoSensors(boolean wantMagnetic, boolean wantAccel, boolean wantGyro) throws InterruptedException {
setToDefault();
SharedPreferences settings = PreferenceManager.getDefaultSharedPreferences(mActivity);
SharedPreferences.Editor editor = settings.edit();
// enable all of the sensors
editor.putBoolean(PreferenceKeys.IMURecordingPreferenceKey, true);
editor.putBoolean(PreferenceKeys.MagnetometerPrefKey, wantMagnetic);
editor.putBoolean(PreferenceKeys.AccelPreferenceKey, wantAccel);
editor.putBoolean(PreferenceKeys.GyroPreferenceKey, wantGyro);
editor.apply();
updateForSettings();

// count initial files in folder
File folder = mActivity.getImageFolder();
Log.d(TAG, "folder: " + folder);
int expectedNFiles = 1;
int nNewFiles = subTestTakeVideo(false, false, true, false, null, 5000, false, expectedNFiles);
return mActivity.getRawSensorInfoManager()
.getLastSensorFilesMap();
}

/* Test recording video with raw IMU sensor info
*/
public void testVideoImuInfoSAF() throws InterruptedException {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,11 @@ public static Test suite() {
TestSuite suite = new TestSuite(MainTests.class.getName());
// Basic video tests
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoImuInfo"));
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoAllSensors"));
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoGyro"));
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoAccel"));
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoMagnetometer"));

suite.addTest(TestSuite.createTest(MainActivityTest.class, "testTakeVideo"));

// TODO: update this test for new video rec stop logic, now it relies on synchronous recording stop
Expand Down
2 changes: 1 addition & 1 deletion app/src/main/assets/server_config.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
RPC_PORT=6969
SERVER_VERSION=v.0.0
SERVER_VERSION=v.0.1
VIDEO_START_REQUEST=video_start
VIDEO_STOP_REQUEST=video_stop
GET_VIDEO_REQUEST=get_video
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@
import net.sourceforge.opencamera.sensorlogging.VideoPhaseInfo;

import java.io.IOException;
import java.util.Date;
import java.util.HashMap;
import java.util.Map;
import java.util.concurrent.BlockingQueue;

/**
Expand All @@ -35,7 +38,7 @@ public VideoFrameInfo setupFrameInfo() throws IOException {

ExtendedAppInterface(MainActivity mainActivity, Bundle savedInstanceState) {
super(mainActivity, savedInstanceState);
mRawSensorInfo = new RawSensorInfo(mainActivity);
mRawSensorInfo = mainActivity.getRawSensorInfoManager();
mMainActivity = mainActivity;
mSharedPreferences = PreferenceManager.getDefaultSharedPreferences(mainActivity);
// We create it only once here (not during the video) as it is a costly operation
Expand Down Expand Up @@ -70,6 +73,10 @@ private boolean getGyroPref() {
return mSharedPreferences.getBoolean(PreferenceKeys.GyroPreferenceKey, true);
}

private boolean getMagneticPref() {
return mSharedPreferences.getBoolean(PreferenceKeys.MagnetometerPrefKey, true);
}

/**
* Retrieves gyroscope and accelerometer sample rate preference and converts it to number
*/
Expand All @@ -93,31 +100,45 @@ public boolean getSaveFramesPref() {
return mSharedPreferences.getBoolean(PreferenceKeys.saveFramesPreferenceKey, false);
}

public void startImu(boolean wantAccel, boolean wantGyro, boolean wantMagnetic, Date currentDate) {
if (wantAccel) {
int accelSampleRate = getSensorSampleRatePref(PreferenceKeys.AccelSampleRatePreferenceKey);
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_ACCELEROMETER, accelSampleRate)) {
mMainActivity.getPreview().showToast(null, "Accelerometer unavailable");
}
}
if (wantGyro) {
int gyroSampleRate = getSensorSampleRatePref(PreferenceKeys.GyroSampleRatePreferenceKey);
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_GYROSCOPE, gyroSampleRate)) {
mMainActivity.getPreview().showToast(null, "Gyroscope unavailable");
}
}
if (wantMagnetic) {
int magneticSampleRate = getSensorSampleRatePref(PreferenceKeys.MagneticSampleRatePreferenceKey);
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_MAGNETIC_FIELD, magneticSampleRate)) {
mMainActivity.getPreview().showToast(null, "Magnetometer unavailable");
}
}

//mRawSensorInfo.startRecording(mMainActivity, mLastVideoDate, get Pref(), getAccelPref())
Map<Integer, Boolean> wantSensorRecordingMap = new HashMap<>();
wantSensorRecordingMap.put(Sensor.TYPE_ACCELEROMETER, getAccelPref());
wantSensorRecordingMap.put(Sensor.TYPE_GYROSCOPE, getGyroPref());
wantSensorRecordingMap.put(Sensor.TYPE_MAGNETIC_FIELD, getMagneticPref());
mRawSensorInfo.startRecording(mMainActivity, currentDate, wantSensorRecordingMap);
}

@Override
public void startingVideo() {
if (MyDebug.LOG) {
Log.d(TAG, "starting video");
}
if (getIMURecordingPref() && useCamera2() && (getGyroPref() || getAccelPref())) {
if (getIMURecordingPref() && useCamera2() && (getGyroPref() || getAccelPref() || getMagneticPref())) {
// Extracting sample rates from shared preferences
try {
if (getAccelPref()) {
int accelSampleRate = getSensorSampleRatePref(PreferenceKeys.AccelSampleRatePreferenceKey);
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_ACCELEROMETER, accelSampleRate)) {
mMainActivity.getPreview().showToast(null, "Accelerometer unavailable");
}
}
if (getGyroPref()) {
int gyroSampleRate = getSensorSampleRatePref(PreferenceKeys.GyroSampleRatePreferenceKey);
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_GYROSCOPE, gyroSampleRate)) {
mMainActivity.getPreview().showToast(null, "Gyroscope unavailable");
// TODO: abort recording?
}
}

mRawSensorInfo.startRecording(mLastVideoDate, getGyroPref(), getAccelPref());
mMainActivity.getPreview().showToast("Starting video with IMU recording...", true);
startImu(getAccelPref(), getGyroPref(), getMagneticPref(), mLastVideoDate);
// TODO: add message to strings.xml
mMainActivity.getPreview().showToast(null, "Starting video with IMU recording");
} catch (NumberFormatException e) {
if (MyDebug.LOG) {
Log.e(TAG, "Failed to retrieve the sample rate preference value");
Expand All @@ -127,7 +148,7 @@ public void startingVideo() {
} else if (getIMURecordingPref() && !useCamera2()) {
mMainActivity.getPreview().showToast(null, "Not using Camera2API! Can't record in sync with IMU");
mMainActivity.getPreview().stopVideo(false);
} else if (getIMURecordingPref() && !(getGyroPref() || getAccelPref())) {
} else if (getIMURecordingPref() && !(getGyroPref() || getMagneticPref() || getAccelPref())) {
mMainActivity.getPreview().showToast(null, "Requested IMU recording but no sensors were enabled");
mMainActivity.getPreview().stopVideo(false);
}
Expand All @@ -144,7 +165,7 @@ public void stoppingVideo() {
mRawSensorInfo.disableSensors();

// TODO: add message to strings.xml
mMainActivity.getPreview().showToast(null, "Finished video with IMU recording");
mMainActivity.getPreview().showToast("Stopping video with IMU recording...", true);
}

super.stoppingVideo();
Expand Down
Loading

0 comments on commit dc04b0e

Please sign in to comment.