Skip to content

Commit 8af96e3

Browse files
committed
State handling improved
1 parent 34d59c5 commit 8af96e3

File tree

1 file changed

+24
-19
lines changed

1 file changed

+24
-19
lines changed

MAVGCL/src/main/java/com/comino/flight/observables/StateProperties.java

+24-19
Original file line numberDiff line numberDiff line change
@@ -141,25 +141,30 @@ private StateProperties(IMAVController control) {
141141

142142
control.getStatusManager().addListener(Status.MSP_CONNECTED, (n) -> {
143143

144-
wq.addSingleTask("LP", 500,() -> {
145-
146-
control.getStatusManager().reset();
147-
148-
isGPSAvailable.set(true);
149-
isGPSAvailable.set(n.isSensorAvailable(Status.MSP_GPS_AVAILABILITY));
150-
isCVAvailable.set(true);
151-
isCVAvailable.set(n.isSensorAvailable(Status.MSP_OPCV_AVAILABILITY));
152-
isSLAMAvailable.set(true);
153-
isSLAMAvailable.set(n.isSensorAvailable(Status.MSP_SLAM_AVAILABILITY));
154-
isMSPAvailable.set(true);
155-
isMSPAvailable.set(n.isSensorAvailable(Status.MSP_MSP_AVAILABILITY));
156-
Platform.runLater(() -> {
157-
simulationProperty.set(n.isStatus(Status.MSP_SITL));
158-
connectedProperty.set(n.isStatus(Status.MSP_CONNECTED));
159-
});
160-
161-
162-
});
144+
// wq.addSingleTask("LP", 500,() -> {
145+
//
146+
// control.getStatusManager().reset();
147+
//
148+
// isGPSAvailable.set(true);
149+
// isGPSAvailable.set(n.isSensorAvailable(Status.MSP_GPS_AVAILABILITY));
150+
// isCVAvailable.set(true);
151+
// isCVAvailable.set(n.isSensorAvailable(Status.MSP_OPCV_AVAILABILITY));
152+
// isSLAMAvailable.set(true);
153+
// isSLAMAvailable.set(n.isSensorAvailable(Status.MSP_SLAM_AVAILABILITY));
154+
// isMSPAvailable.set(true);
155+
// isMSPAvailable.set(n.isSensorAvailable(Status.MSP_MSP_AVAILABILITY));
156+
// Platform.runLater(() -> {
157+
// simulationProperty.set(n.isStatus(Status.MSP_SITL));
158+
// connectedProperty.set(n.isStatus(Status.MSP_CONNECTED));
159+
// });
160+
//
161+
//
162+
// });
163+
164+
Platform.runLater(() -> {
165+
simulationProperty.set(n.isStatus(Status.MSP_SITL));
166+
connectedProperty.set(n.isStatus(Status.MSP_CONNECTED));
167+
});
163168

164169
if(!n.isStatus(Status.MSP_CONNECTED)) {
165170
control.writeLogMessage(new LogMessage("[mgc] Connection to vehicle lost..",MAV_SEVERITY.MAV_SEVERITY_CRITICAL));

0 commit comments

Comments
 (0)