|
60 | 60 | import org.droidplanner.services.android.core.drone.autopilot.px4.Px4Native;
|
61 | 61 | import org.droidplanner.services.android.core.drone.companion.solo.SoloComp;
|
62 | 62 | import org.droidplanner.services.android.core.drone.variables.HeartBeat;
|
| 63 | +import org.droidplanner.services.android.core.drone.variables.StreamRates; |
63 | 64 | import org.droidplanner.services.android.core.drone.variables.calibration.MagnetometerCalibrationImpl;
|
64 | 65 | import org.droidplanner.services.android.core.firmware.FirmwareType;
|
65 | 66 | import org.droidplanner.services.android.core.gcs.GCSHeartbeat;
|
|
77 | 78 | import org.droidplanner.services.android.utils.analytics.GAUtils;
|
78 | 79 | import org.droidplanner.services.android.utils.prefs.DroidPlannerPrefs;
|
79 | 80 |
|
| 81 | +import org.droidplanner.services.android.core.drone.profiles.Parameters; |
| 82 | + |
80 | 83 | import java.util.HashMap;
|
81 | 84 | import java.util.Map;
|
82 | 85 | import java.util.Set;
|
@@ -280,15 +283,26 @@ public void postDelayed(Runnable thread, long timeout) {
|
280 | 283 | break;
|
281 | 284 | }
|
282 | 285 |
|
283 |
| - this.drone.getStreamRates().setRates(dpPrefs.getRates()); |
284 |
| - |
285 | 286 | this.followMe = new Follow(this, handler, new FusedLocation(context, handler));
|
286 | 287 | this.returnToMe = new ReturnToMe(this, new FusedLocation(context, handler,
|
287 | 288 | LocationRequest.PRIORITY_HIGH_ACCURACY, 1000L, 1000L, ReturnToMe.UPDATE_MINIMAL_DISPLACEMENT), this);
|
288 | 289 |
|
| 290 | + final StreamRates streamRates = drone.getStreamRates(); |
| 291 | + if(streamRates != null) { |
| 292 | + streamRates.setRates(dpPrefs.getRates()); |
| 293 | + } |
| 294 | + |
289 | 295 | drone.addDroneListener(this);
|
290 |
| - drone.getParameters().setParameterListener(this); |
291 |
| - drone.getMagnetometerCalibration().setListener(this); |
| 296 | + |
| 297 | + final Parameters parameters = drone.getParameters(); |
| 298 | + if(parameters != null) { |
| 299 | + parameters.setParameterListener(this); |
| 300 | + } |
| 301 | + |
| 302 | + final MagnetometerCalibrationImpl magnetometer = drone.getMagnetometerCalibration(); |
| 303 | + if(magnetometer != null) { |
| 304 | + magnetometer.setListener(this); |
| 305 | + } |
292 | 306 | }
|
293 | 307 |
|
294 | 308 | public SoloComp getSoloComp() {
|
|
0 commit comments