|
7 | 7 |
|
8 | 8 | import com.MAVLink.Messages.MAVLinkMessage;
|
9 | 9 | import com.MAVLink.ardupilotmega.msg_camera_feedback;
|
10 |
| -import com.MAVLink.ardupilotmega.msg_ekf_status_report; |
11 | 10 | import com.MAVLink.ardupilotmega.msg_mag_cal_progress;
|
12 | 11 | import com.MAVLink.ardupilotmega.msg_mag_cal_report;
|
13 | 12 | import com.MAVLink.ardupilotmega.msg_mount_configure;
|
|
41 | 40 | import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
|
42 | 41 | import com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra;
|
43 | 42 | import com.o3dr.services.android.lib.drone.attribute.AttributeType;
|
44 |
| -import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError; |
45 | 43 | import com.o3dr.services.android.lib.drone.mission.action.MissionActions;
|
46 | 44 | import com.o3dr.services.android.lib.drone.property.DroneAttribute;
|
47 |
| -import com.o3dr.services.android.lib.drone.property.VehicleMode; |
48 | 45 | import com.o3dr.services.android.lib.gcs.action.CalibrationActions;
|
49 | 46 | import com.o3dr.services.android.lib.mavlink.MavlinkMessageWrapper;
|
50 | 47 | import com.o3dr.services.android.lib.model.ICommandListener;
|
|
70 | 67 | import org.droidplanner.services.android.core.drone.variables.Magnetometer;
|
71 | 68 | import org.droidplanner.services.android.core.drone.variables.MissionStats;
|
72 | 69 | import org.droidplanner.services.android.core.drone.variables.RC;
|
73 |
| -import org.droidplanner.services.android.core.drone.variables.State; |
74 | 70 | import org.droidplanner.services.android.core.drone.variables.StreamRates;
|
75 |
| -import org.droidplanner.services.android.core.drone.variables.Type; |
76 | 71 | import org.droidplanner.services.android.core.drone.variables.calibration.AccelCalibration;
|
77 | 72 | import org.droidplanner.services.android.core.drone.variables.calibration.MagnetometerCalibrationImpl;
|
78 | 73 | import org.droidplanner.services.android.core.helpers.coordinates.Coord3D;
|
@@ -285,30 +280,29 @@ public void logMessage(int logLevel, String message) {
|
285 | 280 |
|
286 | 281 | @Override
|
287 | 282 | 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); |
294 | 287 |
|
295 |
| - case AttributeType.PARAMETERS: |
296 |
| - return CommonApiUtils.getParameters(this, context); |
| 288 | + case AttributeType.PARAMETERS: |
| 289 | + return CommonApiUtils.getParameters(this, context); |
297 | 290 |
|
298 |
| - case AttributeType.HOME: |
299 |
| - return CommonApiUtils.getHome(this); |
| 291 | + case AttributeType.HOME: |
| 292 | + return CommonApiUtils.getHome(this); |
300 | 293 |
|
301 |
| - case AttributeType.MISSION: |
302 |
| - return CommonApiUtils.getMission(this); |
| 294 | + case AttributeType.MISSION: |
| 295 | + return CommonApiUtils.getMission(this); |
303 | 296 |
|
304 |
| - case AttributeType.TYPE: |
305 |
| - return CommonApiUtils.getType(this); |
| 297 | + case AttributeType.TYPE: |
| 298 | + return CommonApiUtils.getType(this); |
306 | 299 |
|
307 |
| - case AttributeType.GUIDED_STATE: |
308 |
| - return CommonApiUtils.getGuidedState(this); |
| 300 | + case AttributeType.GUIDED_STATE: |
| 301 | + return CommonApiUtils.getGuidedState(this); |
309 | 302 |
|
310 |
| - case AttributeType.MAGNETOMETER_CALIBRATION_STATUS: |
311 |
| - return CommonApiUtils.getMagnetometerCalibrationStatus(this); |
| 303 | + case AttributeType.MAGNETOMETER_CALIBRATION_STATUS: |
| 304 | + return CommonApiUtils.getMagnetometerCalibrationStatus(this); |
| 305 | + } |
312 | 306 | }
|
313 | 307 |
|
314 | 308 | return super.getAttribute(attributeType);
|
@@ -629,13 +623,11 @@ protected void processVfrHud(msg_vfr_hud vfrHud) {
|
629 | 623 | protected void processMountStatus(msg_mount_status mountStatus) {
|
630 | 624 | footprints.updateMountOrientation(mountStatus);
|
631 | 625 |
|
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); |
639 | 631 | }
|
640 | 632 |
|
641 | 633 | private void checkControlSensorsHealth(msg_sys_status sysStatus) {
|
@@ -694,7 +686,7 @@ private void checkArmState(msg_heartbeat msg_heart) {
|
694 | 686 | (msg_heart.base_mode & MAV_MODE_FLAG.MAV_MODE_FLAG_SAFETY_ARMED) == MAV_MODE_FLAG.MAV_MODE_FLAG_SAFETY_ARMED);
|
695 | 687 | }
|
696 | 688 |
|
697 |
| - private void processStatusText(msg_statustext statusText) { |
| 689 | + protected void processStatusText(msg_statustext statusText) { |
698 | 690 | String message = statusText.getText();
|
699 | 691 | if (TextUtils.isEmpty(message))
|
700 | 692 | return;
|
|
0 commit comments