Skip to content

Commit 4147f82

Browse files
committed
fixed npe bug.
1 parent ff2334a commit 4147f82

File tree

1 file changed

+18
-4
lines changed

1 file changed

+18
-4
lines changed

ServiceApp/src/org/droidplanner/services/android/core/drone/DroneManager.java

Lines changed: 18 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,7 @@
6060
import org.droidplanner.services.android.core.drone.autopilot.px4.Px4Native;
6161
import org.droidplanner.services.android.core.drone.companion.solo.SoloComp;
6262
import org.droidplanner.services.android.core.drone.variables.HeartBeat;
63+
import org.droidplanner.services.android.core.drone.variables.StreamRates;
6364
import org.droidplanner.services.android.core.drone.variables.calibration.MagnetometerCalibrationImpl;
6465
import org.droidplanner.services.android.core.firmware.FirmwareType;
6566
import org.droidplanner.services.android.core.gcs.GCSHeartbeat;
@@ -77,6 +78,8 @@
7778
import org.droidplanner.services.android.utils.analytics.GAUtils;
7879
import org.droidplanner.services.android.utils.prefs.DroidPlannerPrefs;
7980

81+
import org.droidplanner.services.android.core.drone.profiles.Parameters;
82+
8083
import java.util.HashMap;
8184
import java.util.Map;
8285
import java.util.Set;
@@ -280,15 +283,26 @@ public void postDelayed(Runnable thread, long timeout) {
280283
break;
281284
}
282285

283-
this.drone.getStreamRates().setRates(dpPrefs.getRates());
284-
285286
this.followMe = new Follow(this, handler, new FusedLocation(context, handler));
286287
this.returnToMe = new ReturnToMe(this, new FusedLocation(context, handler,
287288
LocationRequest.PRIORITY_HIGH_ACCURACY, 1000L, 1000L, ReturnToMe.UPDATE_MINIMAL_DISPLACEMENT), this);
288289

290+
final StreamRates streamRates = drone.getStreamRates();
291+
if(streamRates != null) {
292+
streamRates.setRates(dpPrefs.getRates());
293+
}
294+
289295
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+
}
292306
}
293307

294308
public SoloComp getSoloComp() {

0 commit comments

Comments
 (0)