diff --git a/flutter_app/lib/modules/get_drone_information.dart b/flutter_app/lib/modules/get_drone_information.dart index be4a04a..7f0282f 100644 --- a/flutter_app/lib/modules/get_drone_information.dart +++ b/flutter_app/lib/modules/get_drone_information.dart @@ -1,48 +1,124 @@ import 'dart:async'; +import 'dart:typed_data'; +import 'package:dart_mavlink/mavlink.dart'; +import 'package:dart_mavlink/dialects/common.dart'; import 'package:imacs/modules/mavlink_communication.dart'; class GetDroneInformation { + final MavlinkParser _parser = MavlinkParser(MavlinkDialectCommon()); final MavlinkCommunication comm; - GetDroneInformation({required this.comm}); + final StreamController _yawStreamController = + StreamController(); + final StreamController _pitchStreamController = + StreamController(); + final StreamController _rollStreamController = + StreamController(); + final StreamController _rollSpeedController = + StreamController(); + final StreamController _pitchSpeedController = + StreamController(); + final StreamController _yawSpeedController = + StreamController(); + final StreamController _timeBootMsPitchController = + StreamController(); + + final StreamController _latStreamController = StreamController(); + final StreamController _lonStreamController = StreamController(); + final StreamController _altStreamController = StreamController(); + + GetDroneInformation({required this.comm}) { + if (comm.connectionType == MavlinkCommunicationType.tcp) { + _listenTcpPort(); + } else if (comm.connectionType == MavlinkCommunicationType.serial) { + _listenSerialPort(); + } + _parseMavlinkMessage(); + } + + _listenTcpPort() async { + await comm.tcpSocketInitializationFlag.future; + comm.tcpSocket.listen( + (Uint8List data) { + _parser.parse(data); + }, + onError: (error) { + print(error); + comm.tcpSocket.destroy(); + }, + ); + } + + _listenSerialPort() async { + comm.stream.listen( + (Uint8List data) { + _parser.parse(data); + }, + onError: (error) { + print(error); + comm.serialPort.close(); + }, + ); + } + + void _parseMavlinkMessage() { + _parser.stream.listen((MavlinkFrame frame) { + if (frame.message is Attitude) { + // Append data to appropriate stream + var attitude = frame.message as Attitude; + _yawStreamController.add(attitude.yaw); + _pitchStreamController.add(attitude.pitch); + _rollStreamController.add(attitude.roll); + _rollSpeedController.add(attitude.rollspeed); + _pitchSpeedController.add(attitude.pitchspeed); + _yawSpeedController.add(attitude.yawspeed); + _timeBootMsPitchController.add(attitude.timeBootMs); + } else if (frame.message is GlobalPositionInt) { + var globalPositionInt = frame.message as GlobalPositionInt; + _latStreamController.add(globalPositionInt.lat); + _lonStreamController.add(globalPositionInt.lon); + _altStreamController.add(globalPositionInt.relativeAlt); + } + }); + } Stream getYawStream() { - return comm.yawStreamController.stream; + return _yawStreamController.stream; } Stream getPitchStream() { - return comm.pitchStreamController.stream; + return _pitchStreamController.stream; } Stream getRollStream() { - return comm.rollStreamController.stream; + return _rollStreamController.stream; } Stream getRollSpeedStream() { - return comm.rollSpeedController.stream; + return _rollSpeedController.stream; } Stream getPitchSpeedStream() { - return comm.pitchSpeedController.stream; + return _pitchSpeedController.stream; } Stream getYawSpeedStream() { - return comm.yawSpeedController.stream; + return _yawSpeedController.stream; } Stream getTimeBootMsPitchStream() { - return comm.timeBootMsPitchController.stream; + return _timeBootMsPitchController.stream; } Stream getLatStream() { - return comm.latStreamController.stream; + return _latStreamController.stream; } Stream getLonStream() { - return comm.lonStreamController.stream; + return _lonStreamController.stream; } Stream getAltStream() { - return comm.altStreamController.stream; + return _altStreamController.stream; } } diff --git a/flutter_app/lib/modules/mavlink_communication.dart b/flutter_app/lib/modules/mavlink_communication.dart index 4404a20..ef7762a 100644 --- a/flutter_app/lib/modules/mavlink_communication.dart +++ b/flutter_app/lib/modules/mavlink_communication.dart @@ -11,27 +11,6 @@ enum MavlinkCommunicationType { } class MavlinkCommunication { - final MavlinkParser _parser; - - final StreamController _yawStreamController = - StreamController(); - final StreamController _pitchStreamController = - StreamController(); - final StreamController _rollStreamController = - StreamController(); - final StreamController _rollSpeedController = - StreamController(); - final StreamController _pitchSpeedController = - StreamController(); - final StreamController _yawSpeedController = - StreamController(); - final StreamController _timeBootMsPitchController = - StreamController(); - - final StreamController _latStreamController = StreamController(); - final StreamController _lonStreamController = StreamController(); - final StreamController _altStreamController = StreamController(); - int sequence = 0; // sequence of current message final List waypointQueue = []; @@ -46,8 +25,7 @@ class MavlinkCommunication { MavlinkCommunication(MavlinkCommunicationType connectionType, String connectionAddress, int tcpPort) - : _parser = MavlinkParser(MavlinkDialectCommon()), - _connectionType = connectionType { + : _connectionType = connectionType { switch (_connectionType) { case MavlinkCommunicationType.tcp: _startupTcpPort(connectionAddress, tcpPort); @@ -56,21 +34,11 @@ class MavlinkCommunication { _startupSerialPort(connectionAddress); break; } - - _parseMavlinkMessage(); } _startupTcpPort(String connectionAddress, int tcpPort) async { // Connect to the socket _tcpSocket = await Socket.connect(connectionAddress, tcpPort); - _tcpSocket.listen((Uint8List data) { - _parser.parse(data); - }, onError: (error) { - // print if log does not work, I can't really test it, just avoid the warning - print(error); - _tcpSocket.destroy(); - }); - _tcpSocketInitializationFlag.complete(); } @@ -79,9 +47,6 @@ class MavlinkCommunication { _serialPort.openReadWrite(); SerialPortReader serialPortReader = SerialPortReader(_serialPort); _stream = serialPortReader.stream; - _stream.listen((Uint8List data) { - _parser.parse(data); - }); } _writeToTcpPort(MavlinkFrame frame) { @@ -92,27 +57,6 @@ class MavlinkCommunication { _serialPort.write(frame.serialize()); } - _parseMavlinkMessage() { - _parser.stream.listen((MavlinkFrame frame) { - if (frame.message is Attitude) { - // Append data to appropriate stream - var attitude = frame.message as Attitude; - _yawStreamController.add(attitude.yaw); - _pitchStreamController.add(attitude.pitch); - _rollStreamController.add(attitude.roll); - _rollSpeedController.add(attitude.rollspeed); - _pitchSpeedController.add(attitude.pitchspeed); - _yawSpeedController.add(attitude.yawspeed); - _timeBootMsPitchController.add(attitude.timeBootMs); - } else if (frame.message is GlobalPositionInt) { - var globalPositionInt = frame.message as GlobalPositionInt; - _latStreamController.add(globalPositionInt.lat); - _lonStreamController.add(globalPositionInt.lon); - _altStreamController.add(globalPositionInt.relativeAlt); - } - }); - } - // Send MAVLink messages // Refer to the link below to see how MAVLink frames are sent // https://github.com/nus/dart_mavlink/blob/main/example/parameter.dart @@ -130,15 +74,7 @@ class MavlinkCommunication { MavlinkCommunicationType get connectionType => _connectionType; Completer get tcpSocketInitializationFlag => _tcpSocketInitializationFlag; - StreamController get yawStreamController => _yawStreamController; - StreamController get pitchStreamController => _pitchStreamController; - StreamController get rollStreamController => _rollStreamController; - StreamController get rollSpeedController => _rollSpeedController; - StreamController get pitchSpeedController => _pitchSpeedController; - StreamController get yawSpeedController => _yawSpeedController; - StreamController get timeBootMsPitchController => - _timeBootMsPitchController; - StreamController get latStreamController => _latStreamController; - StreamController get lonStreamController => _lonStreamController; - StreamController get altStreamController => _altStreamController; + Socket get tcpSocket => _tcpSocket; + SerialPort get serialPort => _serialPort; + Stream get stream => _stream; }