File tree 2 files changed +9
-2
lines changed
MAVGCL/src/main/java/com/comino/flight
2 files changed +9
-2
lines changed Original file line number Diff line number Diff line change @@ -177,6 +177,7 @@ public class MainApp extends Application {
177
177
178
178
private final WorkQueue wq = WorkQueue .getInstance ();
179
179
180
+ private AnalysisModelService analysisModelService ;
180
181
private SimpleNTPServer ntp_server ;
181
182
182
183
public MainApp () {
@@ -314,7 +315,7 @@ else if(args.get("ip")!=null)
314
315
MAVGCLMap .getInstance (control );
315
316
MAVGCLPX4Parameters .getInstance (control );
316
317
317
- AnalysisModelService analysisModelService = AnalysisModelService .getInstance (control );
318
+ analysisModelService = AnalysisModelService .getInstance (control );
318
319
analysisModelService .startConverter ();
319
320
320
321
state .getConnectedProperty ().addListener ((e ,o ,n ) -> {
@@ -437,7 +438,7 @@ public void start(Stage primaryStage) {
437
438
@ Override
438
439
public void stop () throws Exception {
439
440
System .out .println ("[mgc] Closing..." );
440
- control . sendMAVLinkCmd ( MAV_CMD . MAV_CMD_LOGGING_STOP );
441
+ analysisModelService . close ( );
441
442
control .shutdown ();
442
443
MAVPreferences .getInstance ().putDouble ("stage.x" , primaryStage .getX ());
443
444
MAVPreferences .getInstance ().putDouble ("stage.y" , primaryStage .getY ());
Original file line number Diff line number Diff line change @@ -188,6 +188,12 @@ public void startConverter() {
188
188
c .setPriority (Thread .NORM_PRIORITY +2 );
189
189
c .start ();
190
190
}
191
+
192
+ public void close () {
193
+ stop ();
194
+ if (ulogger .isLogging ())
195
+ control .sendMAVLinkCmd (MAV_CMD .MAV_CMD_LOGGING_STOP );
196
+ }
191
197
192
198
public void registerListener (ICollectorRecordingListener l ) {
193
199
listener .add (l );
You can’t perform that action at this time.
0 commit comments