Skip to content

Commit

Permalink
Move SteamControllers and _parseMavlinkMessage (#26)
Browse files Browse the repository at this point in the history
* Move SteamControllers and _parseMavlinkMessage from mavlink_communication.dart to get_drone_information.dart

* updated
  • Loading branch information
47vy authored Jul 17, 2024
1 parent 1b3ce62 commit fe57eb9
Show file tree
Hide file tree
Showing 2 changed files with 91 additions and 79 deletions.
98 changes: 87 additions & 11 deletions flutter_app/lib/modules/get_drone_information.dart
Original file line number Diff line number Diff line change
@@ -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<double> _yawStreamController =
StreamController<double>();
final StreamController<double> _pitchStreamController =
StreamController<double>();
final StreamController<double> _rollStreamController =
StreamController<double>();
final StreamController<double> _rollSpeedController =
StreamController<double>();
final StreamController<double> _pitchSpeedController =
StreamController<double>();
final StreamController<double> _yawSpeedController =
StreamController<double>();
final StreamController<int> _timeBootMsPitchController =
StreamController<int>();

final StreamController<int> _latStreamController = StreamController<int>();
final StreamController<int> _lonStreamController = StreamController<int>();
final StreamController<int> _altStreamController = StreamController<int>();

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<double> getYawStream() {
return comm.yawStreamController.stream;
return _yawStreamController.stream;
}

Stream<double> getPitchStream() {
return comm.pitchStreamController.stream;
return _pitchStreamController.stream;
}

Stream<double> getRollStream() {
return comm.rollStreamController.stream;
return _rollStreamController.stream;
}

Stream<double> getRollSpeedStream() {
return comm.rollSpeedController.stream;
return _rollSpeedController.stream;
}

Stream<double> getPitchSpeedStream() {
return comm.pitchSpeedController.stream;
return _pitchSpeedController.stream;
}

Stream<double> getYawSpeedStream() {
return comm.yawSpeedController.stream;
return _yawSpeedController.stream;
}

Stream<int> getTimeBootMsPitchStream() {
return comm.timeBootMsPitchController.stream;
return _timeBootMsPitchController.stream;
}

Stream<int> getLatStream() {
return comm.latStreamController.stream;
return _latStreamController.stream;
}

Stream<int> getLonStream() {
return comm.lonStreamController.stream;
return _lonStreamController.stream;
}

Stream<int> getAltStream() {
return comm.altStreamController.stream;
return _altStreamController.stream;
}
}
72 changes: 4 additions & 68 deletions flutter_app/lib/modules/mavlink_communication.dart
Original file line number Diff line number Diff line change
Expand Up @@ -11,27 +11,6 @@ enum MavlinkCommunicationType {
}

class MavlinkCommunication {
final MavlinkParser _parser;

final StreamController<double> _yawStreamController =
StreamController<double>();
final StreamController<double> _pitchStreamController =
StreamController<double>();
final StreamController<double> _rollStreamController =
StreamController<double>();
final StreamController<double> _rollSpeedController =
StreamController<double>();
final StreamController<double> _pitchSpeedController =
StreamController<double>();
final StreamController<double> _yawSpeedController =
StreamController<double>();
final StreamController<int> _timeBootMsPitchController =
StreamController<int>();

final StreamController<int> _latStreamController = StreamController<int>();
final StreamController<int> _lonStreamController = StreamController<int>();
final StreamController<int> _altStreamController = StreamController<int>();

int sequence = 0; // sequence of current message

final List<MissionItem> waypointQueue = [];
Expand All @@ -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);
Expand All @@ -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();
}

Expand All @@ -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) {
Expand All @@ -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
Expand All @@ -130,15 +74,7 @@ class MavlinkCommunication {
MavlinkCommunicationType get connectionType => _connectionType;
Completer<void> get tcpSocketInitializationFlag =>
_tcpSocketInitializationFlag;
StreamController<double> get yawStreamController => _yawStreamController;
StreamController<double> get pitchStreamController => _pitchStreamController;
StreamController<double> get rollStreamController => _rollStreamController;
StreamController<double> get rollSpeedController => _rollSpeedController;
StreamController<double> get pitchSpeedController => _pitchSpeedController;
StreamController<double> get yawSpeedController => _yawSpeedController;
StreamController<int> get timeBootMsPitchController =>
_timeBootMsPitchController;
StreamController<int> get latStreamController => _latStreamController;
StreamController<int> get lonStreamController => _lonStreamController;
StreamController<int> get altStreamController => _altStreamController;
Socket get tcpSocket => _tcpSocket;
SerialPort get serialPort => _serialPort;
Stream<Uint8List> get stream => _stream;
}

0 comments on commit fe57eb9

Please sign in to comment.