Skip to content

Commit dc04b0e

Browse files
Merge pull request #25 from MobileRoboticsSkoltech/sensor_additional
Add magnetometer recording; Update sensor management logic
2 parents a09afd2 + 8a5cbf6 commit dc04b0e

File tree

19 files changed

+429
-183
lines changed

19 files changed

+429
-183
lines changed

README.md

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22

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

5+
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.
6+
57
## Install
68

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

1416
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.
1517

16-
1718
## Usage
1819

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

3335
### Remote recording
3436

api_client/basic_example.py

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,7 @@
11
import time
22
from src.RemoteControl import RemoteControl
3-
import subprocess
43

5-
HOST = '192.168.1.100' # The smartphone's IP address
4+
HOST = '192.168.1.75' # The smartphone's IP address
65

76

87
def main():
@@ -11,16 +10,16 @@ def main():
1110
remote = RemoteControl(HOST)
1211
print("Connected")
1312

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

1918
phase, duration = remote.start_video()
2019
print("%d %f" % (phase, duration))
2120
time.sleep(5)
2221
remote.stop_video()
23-
22+
2423
# receives last video (blocks until received)
2524
start = time.time()
2625
filename = remote.get_video(want_progress_bar=True)

api_client/src/RemoteControl.py

Lines changed: 13 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -6,9 +6,9 @@
66
BUFFER_SIZE = 4096
77
PROPS_PATH = '../app/src/main/assets/server_config.properties'
88
SUPPORTED_SERVER_VERSIONS = [
9-
'v.0.0'
9+
'v.0.1'
1010
]
11-
11+
NUM_SENSORS = 3
1212

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

29-
def get_imu(self, duration_ms, want_accel, want_gyro):
29+
def get_imu(self, duration_ms, want_accel, want_gyro, want_magnetic):
3030
"""
3131
Request IMU data recording
3232
:param duration_ms: (int) duration in milliseconds
3333
:param want_accel: (boolean) request accelerometer recording
3434
:param want_gyro: (boolean) request gyroscope recording
35-
:return: Tuple (accel_data, gyro_data) - csv data strings
35+
:param want_gyro: (boolean) request magnetometer recording
36+
:return: Tuple (accel_data, gyro_data, magnetic_data) - csv data strings
3637
If one of the sensors wasn't requested, the corresponding data is None
3738
"""
3839
accel = int(want_accel)
3940
gyro = int(want_gyro)
41+
magnetic = int(want_magnetic)
4042
status, socket_file = self._send_and_get_response_status(
41-
'imu?duration=%d&accel=%d&gyro=%d\n' % (duration_ms, accel, gyro)
43+
'imu?duration=%d&accel=%d&gyro=%d&magnetic=%d\n' % (duration_ms, accel, gyro, magnetic)
4244
)
4345
accel_data = None
4446
gyro_data = None
47+
magnetic_data = None
4548

46-
for i in range(2):
49+
for i in range(NUM_SENSORS):
4750
# read filename or end marker
4851
line = socket_file.readline()
4952
msg = line.strip('\n')
@@ -62,8 +65,11 @@ def get_imu(self, duration_ms, want_accel, want_gyro):
6265
accel_data = data
6366
elif msg.endswith("gyro.csv"):
6467
gyro_data = data
68+
elif msg.endswith("magnetic.csv"):
69+
magnetic_data = data
70+
6571
socket_file.close()
66-
return accel_data, gyro_data
72+
return accel_data, gyro_data, magnetic_data
6773

6874
def start_video(self):
6975
"""

app/build.gradle

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ android {
1111
defaultConfig {
1212
applicationId "com.opencamera_extended.app"
1313
minSdkVersion 19
14+
// Important! When we decide to change this to 30 or more, we need to add full support for scoped storage
1415
targetSdkVersion 29
1516

1617
renderscriptTargetApi 21

app/src/androidTest/java/net/sourceforge/opencamera/test/MainActivityTest.java

Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
import java.util.HashSet;
1515
import java.util.List;
1616
import java.util.Locale;
17+
import java.util.Map;
1718
import java.util.Set;
1819

1920
import net.sourceforge.opencamera.LocationSupplier;
@@ -31,6 +32,7 @@
3132
import net.sourceforge.opencamera.SaveLocationHistory;
3233
import net.sourceforge.opencamera.cameracontroller.CameraController;
3334
import net.sourceforge.opencamera.preview.Preview;
35+
import net.sourceforge.opencamera.sensorlogging.RawSensorInfo;
3436
import net.sourceforge.opencamera.ui.FolderChooserDialog;
3537
import net.sourceforge.opencamera.ui.PopupView;
3638

@@ -47,6 +49,7 @@
4749
import android.graphics.Matrix;
4850
import android.graphics.Point;
4951
import android.graphics.PointF;
52+
import android.hardware.Sensor;
5053
import android.hardware.camera2.CameraMetadata;
5154
import android.hardware.camera2.CaptureRequest;
5255
import android.hardware.camera2.params.TonemapCurve;
@@ -7838,6 +7841,64 @@ public void testVideoImuInfo() throws InterruptedException {
78387841
assertEquals(expectedNFiles + 1, nNewFiles);
78397842
}
78407843

7844+
/* Test recording video with all sensors enabled
7845+
Assumes all of the sensors are supported
7846+
*/
7847+
public void testVideoAllSensors() throws InterruptedException {
7848+
Log.d(TAG, "testVideoAllSensors");
7849+
// check sensor files
7850+
Map<Integer, File> sensorFilesMap = subTestVideoSensors(true, true, true);
7851+
assertSensorRecFileExists(Sensor.TYPE_GYROSCOPE, sensorFilesMap);
7852+
assertSensorRecFileExists(Sensor.TYPE_MAGNETIC_FIELD, sensorFilesMap);
7853+
assertSensorRecFileExists(Sensor.TYPE_ACCELEROMETER, sensorFilesMap);
7854+
}
7855+
7856+
public void testVideoMagnetometer() throws InterruptedException {
7857+
Log.d(TAG, "testVideoMagnetometer");
7858+
Map<Integer, File> sensorFilesMap = subTestVideoSensors(true, false, false);
7859+
assertSensorRecFileExists(Sensor.TYPE_MAGNETIC_FIELD, sensorFilesMap);
7860+
}
7861+
7862+
public void testVideoAccel() throws InterruptedException {
7863+
Log.d(TAG, "testVideoAccel");
7864+
Map<Integer, File> sensorFilesMap = subTestVideoSensors(false, true, false);
7865+
assertSensorRecFileExists(Sensor.TYPE_ACCELEROMETER, sensorFilesMap);
7866+
}
7867+
7868+
public void testVideoGyro() throws InterruptedException {
7869+
Log.d(TAG, "testVideoGyro");
7870+
Map<Integer, File> sensorFilesMap = subTestVideoSensors(false, false, true);
7871+
assertSensorRecFileExists(Sensor.TYPE_GYROSCOPE, sensorFilesMap);
7872+
}
7873+
7874+
private void assertSensorRecFileExists(Integer sensorType, Map<Integer, File> sensorFilesMap) {
7875+
assertTrue(
7876+
mActivity.getRawSensorInfoManager().isSensorAvailable(sensorType) &&
7877+
sensorFilesMap.get(sensorType).canRead()
7878+
);
7879+
}
7880+
7881+
public Map<Integer, File> subTestVideoSensors(boolean wantMagnetic, boolean wantAccel, boolean wantGyro) throws InterruptedException {
7882+
setToDefault();
7883+
SharedPreferences settings = PreferenceManager.getDefaultSharedPreferences(mActivity);
7884+
SharedPreferences.Editor editor = settings.edit();
7885+
// enable all of the sensors
7886+
editor.putBoolean(PreferenceKeys.IMURecordingPreferenceKey, true);
7887+
editor.putBoolean(PreferenceKeys.MagnetometerPrefKey, wantMagnetic);
7888+
editor.putBoolean(PreferenceKeys.AccelPreferenceKey, wantAccel);
7889+
editor.putBoolean(PreferenceKeys.GyroPreferenceKey, wantGyro);
7890+
editor.apply();
7891+
updateForSettings();
7892+
7893+
// count initial files in folder
7894+
File folder = mActivity.getImageFolder();
7895+
Log.d(TAG, "folder: " + folder);
7896+
int expectedNFiles = 1;
7897+
int nNewFiles = subTestTakeVideo(false, false, true, false, null, 5000, false, expectedNFiles);
7898+
return mActivity.getRawSensorInfoManager()
7899+
.getLastSensorFilesMap();
7900+
}
7901+
78417902
/* Test recording video with raw IMU sensor info
78427903
*/
78437904
public void testVideoImuInfoSAF() throws InterruptedException {

app/src/androidTest/java/net/sourceforge/opencamera/test/SubsetTests.java

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,11 @@ public static Test suite() {
1111
TestSuite suite = new TestSuite(MainTests.class.getName());
1212
// Basic video tests
1313
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoImuInfo"));
14+
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoAllSensors"));
15+
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoGyro"));
16+
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoAccel"));
17+
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testVideoMagnetometer"));
18+
1419
suite.addTest(TestSuite.createTest(MainActivityTest.class, "testTakeVideo"));
1520

1621
// TODO: update this test for new video rec stop logic, now it relies on synchronous recording stop

app/src/main/assets/server_config.properties

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
RPC_PORT=6969
2-
SERVER_VERSION=v.0.0
2+
SERVER_VERSION=v.0.1
33
VIDEO_START_REQUEST=video_start
44
VIDEO_STOP_REQUEST=video_stop
55
GET_VIDEO_REQUEST=get_video

app/src/main/java/net/sourceforge/opencamera/ExtendedAppInterface.java

Lines changed: 41 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,9 @@
1212
import net.sourceforge.opencamera.sensorlogging.VideoPhaseInfo;
1313

1414
import java.io.IOException;
15+
import java.util.Date;
16+
import java.util.HashMap;
17+
import java.util.Map;
1518
import java.util.concurrent.BlockingQueue;
1619

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

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

76+
private boolean getMagneticPref() {
77+
return mSharedPreferences.getBoolean(PreferenceKeys.MagnetometerPrefKey, true);
78+
}
79+
7380
/**
7481
* Retrieves gyroscope and accelerometer sample rate preference and converts it to number
7582
*/
@@ -93,31 +100,45 @@ public boolean getSaveFramesPref() {
93100
return mSharedPreferences.getBoolean(PreferenceKeys.saveFramesPreferenceKey, false);
94101
}
95102

103+
public void startImu(boolean wantAccel, boolean wantGyro, boolean wantMagnetic, Date currentDate) {
104+
if (wantAccel) {
105+
int accelSampleRate = getSensorSampleRatePref(PreferenceKeys.AccelSampleRatePreferenceKey);
106+
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_ACCELEROMETER, accelSampleRate)) {
107+
mMainActivity.getPreview().showToast(null, "Accelerometer unavailable");
108+
}
109+
}
110+
if (wantGyro) {
111+
int gyroSampleRate = getSensorSampleRatePref(PreferenceKeys.GyroSampleRatePreferenceKey);
112+
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_GYROSCOPE, gyroSampleRate)) {
113+
mMainActivity.getPreview().showToast(null, "Gyroscope unavailable");
114+
}
115+
}
116+
if (wantMagnetic) {
117+
int magneticSampleRate = getSensorSampleRatePref(PreferenceKeys.MagneticSampleRatePreferenceKey);
118+
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_MAGNETIC_FIELD, magneticSampleRate)) {
119+
mMainActivity.getPreview().showToast(null, "Magnetometer unavailable");
120+
}
121+
}
122+
123+
//mRawSensorInfo.startRecording(mMainActivity, mLastVideoDate, get Pref(), getAccelPref())
124+
Map<Integer, Boolean> wantSensorRecordingMap = new HashMap<>();
125+
wantSensorRecordingMap.put(Sensor.TYPE_ACCELEROMETER, getAccelPref());
126+
wantSensorRecordingMap.put(Sensor.TYPE_GYROSCOPE, getGyroPref());
127+
wantSensorRecordingMap.put(Sensor.TYPE_MAGNETIC_FIELD, getMagneticPref());
128+
mRawSensorInfo.startRecording(mMainActivity, currentDate, wantSensorRecordingMap);
129+
}
130+
96131
@Override
97132
public void startingVideo() {
98133
if (MyDebug.LOG) {
99134
Log.d(TAG, "starting video");
100135
}
101-
if (getIMURecordingPref() && useCamera2() && (getGyroPref() || getAccelPref())) {
136+
if (getIMURecordingPref() && useCamera2() && (getGyroPref() || getAccelPref() || getMagneticPref())) {
102137
// Extracting sample rates from shared preferences
103138
try {
104-
if (getAccelPref()) {
105-
int accelSampleRate = getSensorSampleRatePref(PreferenceKeys.AccelSampleRatePreferenceKey);
106-
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_ACCELEROMETER, accelSampleRate)) {
107-
mMainActivity.getPreview().showToast(null, "Accelerometer unavailable");
108-
}
109-
}
110-
if (getGyroPref()) {
111-
int gyroSampleRate = getSensorSampleRatePref(PreferenceKeys.GyroSampleRatePreferenceKey);
112-
if (!mRawSensorInfo.enableSensor(Sensor.TYPE_GYROSCOPE, gyroSampleRate)) {
113-
mMainActivity.getPreview().showToast(null, "Gyroscope unavailable");
114-
// TODO: abort recording?
115-
}
116-
}
117-
118-
mRawSensorInfo.startRecording(mLastVideoDate, getGyroPref(), getAccelPref());
139+
mMainActivity.getPreview().showToast("Starting video with IMU recording...", true);
140+
startImu(getAccelPref(), getGyroPref(), getMagneticPref(), mLastVideoDate);
119141
// TODO: add message to strings.xml
120-
mMainActivity.getPreview().showToast(null, "Starting video with IMU recording");
121142
} catch (NumberFormatException e) {
122143
if (MyDebug.LOG) {
123144
Log.e(TAG, "Failed to retrieve the sample rate preference value");
@@ -127,7 +148,7 @@ public void startingVideo() {
127148
} else if (getIMURecordingPref() && !useCamera2()) {
128149
mMainActivity.getPreview().showToast(null, "Not using Camera2API! Can't record in sync with IMU");
129150
mMainActivity.getPreview().stopVideo(false);
130-
} else if (getIMURecordingPref() && !(getGyroPref() || getAccelPref())) {
151+
} else if (getIMURecordingPref() && !(getGyroPref() || getMagneticPref() || getAccelPref())) {
131152
mMainActivity.getPreview().showToast(null, "Requested IMU recording but no sensors were enabled");
132153
mMainActivity.getPreview().stopVideo(false);
133154
}
@@ -144,7 +165,7 @@ public void stoppingVideo() {
144165
mRawSensorInfo.disableSensors();
145166

146167
// TODO: add message to strings.xml
147-
mMainActivity.getPreview().showToast(null, "Finished video with IMU recording");
168+
mMainActivity.getPreview().showToast("Stopping video with IMU recording...", true);
148169
}
149170

150171
super.stoppingVideo();

0 commit comments

Comments
 (0)