Skip to content

Commit

Permalink
Merge pull request #132 from DroidPlanner/feature_magnetometer_calibr…
Browse files Browse the repository at this point in the history
…ation

Feature magnetometer calibration
  • Loading branch information
m4gr3d committed May 5, 2015
2 parents b3ae2b4 + 6b0ae07 commit 0341be4
Show file tree
Hide file tree
Showing 29 changed files with 895 additions and 553 deletions.
6 changes: 3 additions & 3 deletions ClientLib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ apply plugin: 'com.android.library'

ext {
PUBLISH_ARTIFACT_ID = 'dronekit-android'
PUBLISH_VERSION = '2.3.13'
PUBLISH_VERSION = '2.3.25'
PROJECT_DESCRIPTION = "Android DroneKit client library."
PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android', 'DroneKit']
PROJECT_LICENSES = ['Apache-2.0']
Expand All @@ -17,7 +17,7 @@ android {
defaultConfig {
minSdkVersion 14
targetSdkVersion 21
versionCode 20313
versionCode 20325
versionName PUBLISH_VERSION
}

Expand All @@ -40,7 +40,7 @@ android {
variant.outputs.each { output ->
def file = output.outputFile
if (file != null && file.name.endsWith('.aar')) {
output.outputFile = new File(file.parent, "${PUBLISH_ARTIFACT_ID}.${PUBLISH_VERSION}.aar")
output.outputFile = new File(file.parent, "${PUBLISH_ARTIFACT_ID}.${PUBLISH_VERSION}.aar")
}
}
}
Expand Down
81 changes: 20 additions & 61 deletions ClientLib/src/main/java/com/o3dr/android/client/Drone.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package com.o3dr.android.client;

import android.content.Context;
import android.os.Bundle;
import android.os.Handler;
import android.os.IBinder;
Expand All @@ -20,6 +21,7 @@
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
import com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationStatus;
import com.o3dr.services.android.lib.drone.camera.GoPro;
import com.o3dr.services.android.lib.drone.connection.ConnectionParameter;
import com.o3dr.services.android.lib.drone.connection.ConnectionResult;
Expand Down Expand Up @@ -109,7 +111,11 @@ public void binderDied() {
private long startTime = 0;
private long elapsedFlightTime = 0;

public Drone(){}
private final Context context;

public Drone(Context context){
this.context = context;
}

void init(ControlTower controlTower, Handler handler){
this.handler = handler;
Expand Down Expand Up @@ -232,7 +238,7 @@ public <T extends Parcelable> T getAttribute(String type) {
}

if (carrier != null) {
ClassLoader classLoader = getAttributeClassLoader(type);
ClassLoader classLoader = this.context.getClassLoader();
if (classLoader != null) {
carrier.setClassLoader(classLoader);
attribute = carrier.getParcelable(type);
Expand Down Expand Up @@ -317,59 +323,10 @@ private <T extends Parcelable> T getAttributeDefaultValue(String attributeType)
case AttributeType.GOPRO:
return (T) new GoPro();

case AttributeType.CAMERA:
default:
return null;
}
}

private ClassLoader getAttributeClassLoader(String attributeType) {
switch (attributeType) {
case AttributeType.ALTITUDE:
return Altitude.class.getClassLoader();

case AttributeType.GPS:
return Gps.class.getClassLoader();

case AttributeType.STATE:
return State.class.getClassLoader();

case AttributeType.PARAMETERS:
return Parameters.class.getClassLoader();

case AttributeType.SPEED:
return Speed.class.getClassLoader();
case AttributeType.MAGNETOMETER_CALIBRATION_STATUS:
return (T) new MagnetometerCalibrationStatus();

case AttributeType.CAMERA:
return CameraProxy.class.getClassLoader();

case AttributeType.ATTITUDE:
return Attitude.class.getClassLoader();

case AttributeType.HOME:
return Home.class.getClassLoader();

case AttributeType.BATTERY:
return Battery.class.getClassLoader();

case AttributeType.MISSION:
return Mission.class.getClassLoader();

case AttributeType.SIGNAL:
return Signal.class.getClassLoader();

case AttributeType.GUIDED_STATE:
return GuidedState.class.getClassLoader();

case AttributeType.TYPE:
return Type.class.getClassLoader();

case AttributeType.FOLLOW_STATE:
return FollowState.class.getClassLoader();

case AttributeType.GOPRO:
return GoPro.class.getClassLoader();

default:
return null;
}
Expand Down Expand Up @@ -527,18 +484,16 @@ public void arm(boolean arm) {
DroneStateApi.arm(this, arm);
}

public void startMagnetometerCalibration(double[] startPointsX, double[] startPointsY, double[] startPointsZ) {
CalibrationApi.startMagnetometerCalibration(this, startPointsX, startPointsY, startPointsZ);
}

public void stopMagnetometerCalibration() {
CalibrationApi.stopMagnetometerCalibration(this);
}

/**
* @deprecated Use {@link CalibrationApi#startIMUCalibration(Drone)} instead.
*/
public void startIMUCalibration() {
CalibrationApi.startIMUCalibration(this);
}

/**
* @deprecated Use {@link CalibrationApi#sendIMUAck(Drone, int)} instead.
*/
public void sendIMUCalibrationAck(int step) {
CalibrationApi.sendIMUAck(this, step);
}
Expand Down Expand Up @@ -597,6 +552,10 @@ public void run() {
}

void notifyAttributeUpdated(final String attributeEvent, final Bundle extras) {
//Update the bundle classloader
if(extras != null)
extras.setClassLoader(context.getClassLoader());

if (AttributeEvent.STATE_UPDATED.equals(attributeEvent)) {
getAttributeAsync(AttributeType.STATE, new OnAttributeRetrievedCallback<State>() {
@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,15 @@
import com.o3dr.android.client.Drone;
import com.o3dr.services.android.lib.model.action.Action;

import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.ACTION_ACCEPT_MAGNETOMETER_CALIBRATION;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.ACTION_CANCEL_MAGNETOMETER_CALIBRATION;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.ACTION_SEND_IMU_CALIBRATION_ACK;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.ACTION_START_IMU_CALIBRATION;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.ACTION_START_MAGNETOMETER_CALIBRATION;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.ACTION_STOP_MAGNETOMETER_CALIBRATION;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.EXTRA_IMU_STEP;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.EXTRA_MAGNETOMETER_START_X;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.EXTRA_MAGNETOMETER_START_Y;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.EXTRA_MAGNETOMETER_START_Z;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.EXTRA_RETRY_ON_FAILURE;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.EXTRA_SAVE_AUTOMATICALLY;
import static com.o3dr.services.android.lib.gcs.action.CalibrationActions.EXTRA_START_DELAY;

/**
* Created by Fredia Huya-Kouadio on 1/19/15.
Expand All @@ -37,22 +38,36 @@ public static void sendIMUAck(Drone drone, int step) {

/**
* Start the magnetometer calibration process.
*
* @param startPoints points to start the calibration with.
*/
public static void startMagnetometerCalibration(Drone drone, double[] pointsX, double[] pointsY, double[] pointsZ) {
public static void startMagnetometerCalibration(Drone drone) {
startMagnetometerCalibration(drone, false, true, 0);
}

/**
* Start the magnetometer calibration process
* @param drone vehicle to calibrate
* @param retryOnFailure if true, automatically retry the magnetometer calibration if it fails
* @param saveAutomatically if true, save the calibration automatically without user input.
* @param startDelay positive delay in seconds before starting the calibration
*/
public static void startMagnetometerCalibration(Drone drone, boolean retryOnFailure, boolean saveAutomatically,
int startDelay){
Bundle params = new Bundle();
params.putDoubleArray(EXTRA_MAGNETOMETER_START_X, pointsX);
params.putDoubleArray(EXTRA_MAGNETOMETER_START_Y, pointsY);
params.putDoubleArray(EXTRA_MAGNETOMETER_START_Z, pointsZ);
params.putBoolean(EXTRA_RETRY_ON_FAILURE, retryOnFailure);
params.putBoolean(EXTRA_SAVE_AUTOMATICALLY, saveAutomatically);
params.putInt(EXTRA_START_DELAY, startDelay);

drone.performAsyncAction(new Action(ACTION_START_MAGNETOMETER_CALIBRATION, params));
}

public static void acceptMagnetometerCalibration(Drone drone) {
drone.performAsyncAction(new Action(ACTION_ACCEPT_MAGNETOMETER_CALIBRATION));
}

/**
* Stop the magnetometer calibration is one if running.
* Cancel the magnetometer calibration is one if running.
*/
public static void stopMagnetometerCalibration(Drone drone) {
drone.performAsyncAction(new Action(ACTION_STOP_MAGNETOMETER_CALIBRATION));
public static void cancelMagnetometerCalibration(Drone drone) {
drone.performAsyncAction(new Action(ACTION_CANCEL_MAGNETOMETER_CALIBRATION));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -26,20 +26,21 @@ public class AttributeEvent {
public static final String AUTOPILOT_MESSAGE = PACKAGE_NAME + ".AUTOPILOT_MESSAGE";

/**
* Signals the start of magnetometer calibration.
* Event to signal cancellation of the magnetometer calibration process.
*/
public static final String CALIBRATION_MAG_STARTED = PACKAGE_NAME +
".CALIBRATION_MAG_STARTED";
public static final String CALIBRATION_MAG_CANCELLED = PACKAGE_NAME + ".CALIBRATION_MAG_CANCELLED";

/**
* Signals a magnetometer calibration fitness update.
* Signals completion of the magnetometer calibration.
* @see {@link AttributeEventExtra#EXTRA_CALIBRATION_MAG_RESULT}
*/
public static final String CALIBRATION_MAG_ESTIMATION = PACKAGE_NAME +
".CALIBRATION_MAG_ESTIMATION";
public static final String CALIBRATION_MAG_COMPLETED = PACKAGE_NAME + ".CALIBRATION_MAG_COMPLETED";

/**
* Signals completion of the magnetometer calibration.
* Provides progress updates for the magnetometer calibration.
* @see {@link AttributeEventExtra#EXTRA_CALIBRATION_MAG_PROGRESS}
*/
public static final String CALIBRATION_MAG_COMPLETED = PACKAGE_NAME +
".CALIBRATION_MAG_COMPLETED";
public static final String CALIBRATION_MAG_PROGRESS = PACKAGE_NAME + ".CALIBRATION_MAG_PROGRESS";

public static final String CALIBRATION_IMU = PACKAGE_NAME + ".CALIBRATION_IMU";
public static final String CALIBRATION_IMU_ERROR = PACKAGE_NAME + ".CALIBRATION_IMU_ERROR";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,34 +28,16 @@ public class AttributeEventExtra {
public static final String EXTRA_CALIBRATION_IMU_MESSAGE = PACKAGE_NAME + ".CALIBRATION_IMU_MESSAGE";

/**
* Used to access the points used to start the magnetometer calibration.
* Used to access the magnetometer calibration progress.
* @see {@link com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationProgress}
*/
public static final String EXTRA_CALIBRATION_MAG_POINTS_X = PACKAGE_NAME + "" +
".CALIBRATION_MAG_POINTS_X";
public static final String EXTRA_CALIBRATION_MAG_POINTS_Y = PACKAGE_NAME + "" +
".CALIBRATION_MAG_POINTS_Y";
public static final String EXTRA_CALIBRATION_MAG_POINTS_Z = PACKAGE_NAME + "" +
".CALIBRATION_MAG_POINTS_Z";
/**
* Used to access the magnetometer calibration fitness value.
*/
public static final String EXTRA_CALIBRATION_MAG_FITNESS = PACKAGE_NAME + "" +
".CALIBRATION_MAG_FITNESS";
/**
* Used to access the magnetometer calibration fit center values.
*/
public static final String EXTRA_CALIBRATION_MAG_FIT_CENTER = PACKAGE_NAME + "" +
".CALIBRATION_MAG_FIT_CENTER";
/**
* Used to access the magnetometer calibration fit radii values.
*/
public static final String EXTRA_CALIBRATION_MAG_FIT_RADII = PACKAGE_NAME + "" +
".CALIBRATION_MAG_FIT_RADII";
public static final String EXTRA_CALIBRATION_MAG_PROGRESS = PACKAGE_NAME + ".CALIBRATION_MAG_PROGRESS";

/**
* Used to access the magnetometer calibration final offset values.
* Used to access the result from the magnetometer calibration.
* @see {@link com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationResult}
*/
public static final String EXTRA_CALIBRATION_MAG_OFFSETS = PACKAGE_NAME + "" +
".CALIBRATION_MAG_OFFSETS";
public static final String EXTRA_CALIBRATION_MAG_RESULT = PACKAGE_NAME + ".CALIBRATION_MAG_RESULT";

/**
* Used to access the mavlink version when the heartbeat is received for the first time or
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,4 +97,10 @@ public class AttributeType {
* @see {@link com.o3dr.services.android.lib.drone.camera.GoPro}
*/
public static final String GOPRO = PACKAGE_NAME + ".GOPRO";

/**
* Used to retrieve the status of the currently or last running magnetometer calibration.
* @see {@link com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationStatus}
*/
public static final String MAGNETOMETER_CALIBRATION_STATUS = PACKAGE_NAME + ".MAGNETOMETER_CALIBRATION_STATUS";
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
package com.o3dr.services.android.lib.drone.calibration.magnetometer;

parcelable MagnetometerCalibrationProgress;
Loading

0 comments on commit 0341be4

Please sign in to comment.