-
Notifications
You must be signed in to change notification settings - Fork 2
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Move SteamControllers and _parseMavlinkMessage #26
Merged
Merged
Changes from all commits
Commits
Show all changes
2 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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; | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Move this logic to
GetDroneInformation