Skip to content

Commit 05e034c

Browse files
committed
Merge pull request #281 from dronekit/feature_autopilot_uid
Feature autopilot uid
2 parents 541780f + 089a414 commit 05e034c

File tree

5 files changed

+99
-34
lines changed

5 files changed

+99
-34
lines changed

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEvent.java

+6
Original file line numberDiff line numberDiff line change
@@ -170,6 +170,12 @@ private AttributeEvent() {
170170
*/
171171
public static final String STATE_VEHICLE_VIBRATION = PACKAGE_NAME + ".STATE_VEHICLE_VIBRATION";
172172

173+
/**
174+
* Signals vehicle UID updates.
175+
* @see {@link com.o3dr.services.android.lib.drone.property.State}
176+
*/
177+
public static final String STATE_VEHICLE_UID = PACKAGE_NAME + ".STATE_VEHICLE_UID";
178+
173179
/**
174180
* Home attribute events.
175181
*/

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/property/State.java

+12
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@ public class State implements DroneAttribute {
2525

2626
private Vibration vehicleVibration = new Vibration();
2727

28+
private String vehicleUid;
29+
2830
public State() {
2931
}
3032

@@ -144,6 +146,14 @@ public Vibration getVehicleVibration() {
144146
return vehicleVibration;
145147
}
146148

149+
public String getVehicleUid() {
150+
return vehicleUid;
151+
}
152+
153+
public void setVehicleUid(String vehicleUid) {
154+
this.vehicleUid = vehicleUid;
155+
}
156+
147157
@Override
148158
public int describeContents() {
149159
return 0;
@@ -162,6 +172,7 @@ public void writeToParcel(Parcel dest, int flags) {
162172
dest.writeParcelable(this.ekfStatus, 0);
163173
dest.writeByte(isTelemetryLive ? (byte) 1 : (byte) 0);
164174
dest.writeParcelable(this.vehicleVibration, 0);
175+
dest.writeString(this.vehicleUid);
165176
}
166177

167178
private State(Parcel in) {
@@ -176,6 +187,7 @@ private State(Parcel in) {
176187
this.ekfStatus = in.readParcelable(EkfStatus.class.getClassLoader());
177188
this.isTelemetryLive = in.readByte() != 0;
178189
this.vehicleVibration = in.readParcelable(Vibration.class.getClassLoader());
190+
this.vehicleUid = in.readString();
179191
}
180192

181193
public static final Creator<State> CREATOR = new Creator<State>() {

ServiceApp/src/org/droidplanner/services/android/core/drone/autopilot/CommonMavLinkDrone.java

+13-3
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ public abstract class CommonMavLinkDrone implements MavLinkDrone {
5050
protected final Type type;
5151
private final State state;
5252

53-
protected final DroneInterfaces.AttributeEventListener attributeListener;
53+
private final DroneInterfaces.AttributeEventListener attributeListener;
5454

5555
protected final Altitude altitude = new Altitude();
5656
protected final Speed speed = new Speed();
@@ -89,6 +89,16 @@ public void removeDroneListener(DroneInterfaces.OnDroneListener listener) {
8989
events.removeDroneListener(listener);
9090
}
9191

92+
protected void notifyAttributeListener(String attributeEvent){
93+
notifyAttributeListener(attributeEvent, null);
94+
}
95+
96+
protected void notifyAttributeListener(String attributeEvent, Bundle eventInfo){
97+
if(attributeListener != null){
98+
attributeListener.onAttributeEvent(attributeEvent, eventInfo);
99+
}
100+
}
101+
92102
@Override
93103
public void notifyDroneEvent(final DroneInterfaces.DroneEventsType event) {
94104
switch (event) {
@@ -229,8 +239,8 @@ private void processVibrationMessage(msg_vibration vibrationMsg){
229239
wasUpdated = true;
230240
}
231241

232-
if(wasUpdated && attributeListener != null){
233-
attributeListener.onAttributeEvent(AttributeEvent.STATE_VEHICLE_VIBRATION, null);
242+
if(wasUpdated){
243+
notifyAttributeListener(AttributeEvent.STATE_VEHICLE_VIBRATION);
234244
}
235245
}
236246

ServiceApp/src/org/droidplanner/services/android/core/drone/autopilot/apm/ArduPilot.java

+23-31
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,6 @@
77

88
import com.MAVLink.Messages.MAVLinkMessage;
99
import com.MAVLink.ardupilotmega.msg_camera_feedback;
10-
import com.MAVLink.ardupilotmega.msg_ekf_status_report;
1110
import com.MAVLink.ardupilotmega.msg_mag_cal_progress;
1211
import com.MAVLink.ardupilotmega.msg_mag_cal_report;
1312
import com.MAVLink.ardupilotmega.msg_mount_configure;
@@ -41,10 +40,8 @@
4140
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
4241
import com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra;
4342
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
44-
import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError;
4543
import com.o3dr.services.android.lib.drone.mission.action.MissionActions;
4644
import com.o3dr.services.android.lib.drone.property.DroneAttribute;
47-
import com.o3dr.services.android.lib.drone.property.VehicleMode;
4845
import com.o3dr.services.android.lib.gcs.action.CalibrationActions;
4946
import com.o3dr.services.android.lib.mavlink.MavlinkMessageWrapper;
5047
import com.o3dr.services.android.lib.model.ICommandListener;
@@ -70,9 +67,7 @@
7067
import org.droidplanner.services.android.core.drone.variables.Magnetometer;
7168
import org.droidplanner.services.android.core.drone.variables.MissionStats;
7269
import org.droidplanner.services.android.core.drone.variables.RC;
73-
import org.droidplanner.services.android.core.drone.variables.State;
7470
import org.droidplanner.services.android.core.drone.variables.StreamRates;
75-
import org.droidplanner.services.android.core.drone.variables.Type;
7671
import org.droidplanner.services.android.core.drone.variables.calibration.AccelCalibration;
7772
import org.droidplanner.services.android.core.drone.variables.calibration.MagnetometerCalibrationImpl;
7873
import org.droidplanner.services.android.core.helpers.coordinates.Coord3D;
@@ -285,30 +280,29 @@ public void logMessage(int logLevel, String message) {
285280

286281
@Override
287282
public DroneAttribute getAttribute(String attributeType) {
288-
if (TextUtils.isEmpty(attributeType))
289-
return null;
290-
291-
switch (attributeType) {
292-
case AttributeType.GPS:
293-
return CommonApiUtils.getGps(this);
283+
if (!TextUtils.isEmpty(attributeType)) {
284+
switch (attributeType) {
285+
case AttributeType.GPS:
286+
return CommonApiUtils.getGps(this);
294287

295-
case AttributeType.PARAMETERS:
296-
return CommonApiUtils.getParameters(this, context);
288+
case AttributeType.PARAMETERS:
289+
return CommonApiUtils.getParameters(this, context);
297290

298-
case AttributeType.HOME:
299-
return CommonApiUtils.getHome(this);
291+
case AttributeType.HOME:
292+
return CommonApiUtils.getHome(this);
300293

301-
case AttributeType.MISSION:
302-
return CommonApiUtils.getMission(this);
294+
case AttributeType.MISSION:
295+
return CommonApiUtils.getMission(this);
303296

304-
case AttributeType.TYPE:
305-
return CommonApiUtils.getType(this);
297+
case AttributeType.TYPE:
298+
return CommonApiUtils.getType(this);
306299

307-
case AttributeType.GUIDED_STATE:
308-
return CommonApiUtils.getGuidedState(this);
300+
case AttributeType.GUIDED_STATE:
301+
return CommonApiUtils.getGuidedState(this);
309302

310-
case AttributeType.MAGNETOMETER_CALIBRATION_STATUS:
311-
return CommonApiUtils.getMagnetometerCalibrationStatus(this);
303+
case AttributeType.MAGNETOMETER_CALIBRATION_STATUS:
304+
return CommonApiUtils.getMagnetometerCalibrationStatus(this);
305+
}
312306
}
313307

314308
return super.getAttribute(attributeType);
@@ -629,13 +623,11 @@ protected void processVfrHud(msg_vfr_hud vfrHud) {
629623
protected void processMountStatus(msg_mount_status mountStatus) {
630624
footprints.updateMountOrientation(mountStatus);
631625

632-
if (attributeListener != null) {
633-
final Bundle eventInfo = new Bundle(3);
634-
eventInfo.putFloat(AttributeEventExtra.EXTRA_GIMBAL_ORIENTATION_PITCH, mountStatus.pointing_a / 100f);
635-
eventInfo.putFloat(AttributeEventExtra.EXTRA_GIMBAL_ORIENTATION_ROLL, mountStatus.pointing_b / 100f);
636-
eventInfo.putFloat(AttributeEventExtra.EXTRA_GIMBAL_ORIENTATION_YAW, mountStatus.pointing_c / 100f);
637-
attributeListener.onAttributeEvent(AttributeEvent.GIMBAL_ORIENTATION_UPDATED, eventInfo);
638-
}
626+
final Bundle eventInfo = new Bundle(3);
627+
eventInfo.putFloat(AttributeEventExtra.EXTRA_GIMBAL_ORIENTATION_PITCH, mountStatus.pointing_a / 100f);
628+
eventInfo.putFloat(AttributeEventExtra.EXTRA_GIMBAL_ORIENTATION_ROLL, mountStatus.pointing_b / 100f);
629+
eventInfo.putFloat(AttributeEventExtra.EXTRA_GIMBAL_ORIENTATION_YAW, mountStatus.pointing_c / 100f);
630+
notifyAttributeListener(AttributeEvent.GIMBAL_ORIENTATION_UPDATED, eventInfo);
639631
}
640632

641633
private void checkControlSensorsHealth(msg_sys_status sysStatus) {
@@ -694,7 +686,7 @@ private void checkArmState(msg_heartbeat msg_heart) {
694686
(msg_heart.base_mode & MAV_MODE_FLAG.MAV_MODE_FLAG_SAFETY_ARMED) == MAV_MODE_FLAG.MAV_MODE_FLAG_SAFETY_ARMED);
695687
}
696688

697-
private void processStatusText(msg_statustext statusText) {
689+
protected void processStatusText(msg_statustext statusText) {
698690
String message = statusText.getText();
699691
if (TextUtils.isEmpty(message))
700692
return;

ServiceApp/src/org/droidplanner/services/android/core/drone/autopilot/apm/ArduSolo.java

+45
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,11 @@
33
import android.content.Context;
44
import android.text.TextUtils;
55

6+
import com.MAVLink.common.msg_statustext;
67
import com.MAVLink.enums.MAV_TYPE;
8+
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
79
import com.o3dr.services.android.lib.drone.property.DroneAttribute;
10+
import com.o3dr.services.android.lib.drone.property.State;
811

912
import org.droidplanner.services.android.core.MAVLink.MAVLinkStreams;
1013
import org.droidplanner.services.android.core.drone.DroneInterfaces;
@@ -13,11 +16,21 @@
1316
import org.droidplanner.services.android.core.firmware.FirmwareType;
1417
import org.droidplanner.services.android.core.model.AutopilotWarningParser;
1518

19+
import java.util.regex.Matcher;
20+
import java.util.regex.Pattern;
21+
22+
import timber.log.Timber;
23+
1624
/**
1725
* Created by Fredia Huya-Kouadio on 7/27/15.
1826
*/
1927
public class ArduSolo extends ArduCopter {
2028

29+
private static final String PIXHAWK_SERIAL_NUMBER_REGEX = ".*PX4v2 (([0-9A-F]{8}) ([0-9A-F]{8}) ([0-9A-F]{8}))";
30+
private static final Pattern PIXHAWK_SERIAL_NUMBER_PATTERN = Pattern.compile(PIXHAWK_SERIAL_NUMBER_REGEX);
31+
32+
private String pixhawkSerialNumber;
33+
2134
public ArduSolo(Context context, MAVLinkStreams.MAVLinkOutputStream mavClient, DroneInterfaces.Handler handler, Preferences pref, AutopilotWarningParser warningParser, LogMessageListener logListener, DroneInterfaces.AttributeEventListener listener) {
2235
super(context, mavClient, handler, pref, warningParser, logListener, listener);
2336
}
@@ -35,6 +48,16 @@ public FirmwareType getFirmwareType() {
3548
return FirmwareType.ARDU_SOLO;
3649
}
3750

51+
@Override
52+
public DroneAttribute getAttribute(String attributeType){
53+
final DroneAttribute attribute = super.getAttribute(attributeType);
54+
if(attribute instanceof State){
55+
((State) attribute).setVehicleUid(pixhawkSerialNumber);
56+
}
57+
58+
return attribute;
59+
}
60+
3861
@Override
3962
protected void processSignalUpdate(int rxerrors, int fixed, short rssi, short remrssi, short txbuf,
4063
short noise, short remnoise){
@@ -54,4 +77,26 @@ protected void processSignalUpdate(int rxerrors, int fixed, short rssi, short re
5477

5578
notifyDroneEvent(DroneInterfaces.DroneEventsType.RADIO);
5679
}
80+
81+
@Override
82+
protected void processStatusText(msg_statustext statusText){
83+
super.processStatusText(statusText);
84+
85+
final String message = statusText.getText();
86+
if (!TextUtils.isEmpty(message)) {
87+
88+
//Parse pixhawk serial number.
89+
final Matcher matcher = PIXHAWK_SERIAL_NUMBER_PATTERN.matcher(message);
90+
if(matcher.matches()){
91+
Timber.i("Received serial number: %s", message);
92+
93+
final String serialNumber = matcher.group(2) + matcher.group(3) + matcher.group(4);
94+
if(!serialNumber.equalsIgnoreCase(pixhawkSerialNumber)){
95+
pixhawkSerialNumber = serialNumber;
96+
97+
notifyAttributeListener(AttributeEvent.STATE_VEHICLE_UID);
98+
}
99+
}
100+
}
101+
}
57102
}

0 commit comments

Comments
 (0)