diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS new file mode 100644 index 00000000..d4b04d03 --- /dev/null +++ b/.github/CODEOWNERS @@ -0,0 +1,3 @@ +# Levi has to review everything + +* @Levi-Lesches diff --git a/.github/workflows/analyze.yml b/.github/workflows/analyze.yml index d0ed0697..b6f41da1 100644 --- a/.github/workflows/analyze.yml +++ b/.github/workflows/analyze.yml @@ -16,6 +16,8 @@ jobs: # You can specify other versions if desired, see documentation here: # https://github.com/dart-lang/setup-dart/blob/main/README.md - uses: dart-lang/setup-dart@v1 + with: + sdk: 3.2.2 - name: Install dependencies run: dart pub get diff --git a/Protobuf b/Protobuf index 53b99d47..d058c6cd 160000 --- a/Protobuf +++ b/Protobuf @@ -1 +1 @@ -Subproject commit 53b99d47718c136f03518ed4dd79fc7027cdcae2 +Subproject commit d058c6cdc9bb0e320945e9b7f6b4e614468b89e0 diff --git a/analysis_options.yaml b/analysis_options.yaml index 91075cd8..99d8efa7 100644 --- a/analysis_options.yaml +++ b/analysis_options.yaml @@ -47,4 +47,4 @@ linter: cascade_invocations: false # sometimes, multi-line code is more readable # Temporarily disabled until we are ready to document - public_member_api_docs: false + # public_member_api_docs: false diff --git a/bin/logs.dart b/bin/logs.dart index 0747a5d3..30b66894 100644 --- a/bin/logs.dart +++ b/bin/logs.dart @@ -1,5 +1,4 @@ import "package:burt_network/burt_network.dart"; -import "package:burt_network/logging.dart"; // 1. Define a new socket on port 8001 that doesn't do anything class LogsServer extends RoverServer { @@ -9,7 +8,10 @@ class LogsServer extends RoverServer { void onMessage(_) { } @override - void restart() { } + Future restart() async { } + + @override + Future onShutdown() async { } } // 2. Create that socket and make a logger that uses it. diff --git a/example/server.dart b/example/server.dart index 4ce45c4f..c3cba9bd 100644 --- a/example/server.dart +++ b/example/server.dart @@ -1,5 +1,4 @@ import "package:burt_network/burt_network.dart"; -import "package:burt_network/logging.dart"; final logger = BurtLogger(); diff --git a/lib/burt_network.dart b/lib/burt_network.dart index 9d8d62f9..c021aac9 100644 --- a/lib/burt_network.dart +++ b/lib/burt_network.dart @@ -19,18 +19,26 @@ library; // For doc comments: -import "src/burt_protocol.dart"; -import "src/proto_socket.dart"; -import "src/rover_heartbeats.dart"; -import "src/rover_logger.dart"; -import "src/rover_server.dart"; -import "src/udp_socket.dart"; +import "src/udp/burt_protocol.dart"; +import "src/udp/proto_socket.dart"; +import "src/udp/rover_heartbeats.dart"; +import "src/udp/rover_logger.dart"; +import "src/udp/rover_server.dart"; +import "src/udp/udp_socket.dart"; -export "src/proto_socket.dart"; -export "src/rover_server.dart"; -export "src/burt_protocol.dart"; -export "src/rover_heartbeats.dart"; -export "src/socket_info.dart"; -export "src/udp_socket.dart"; +export "src/udp/proto_socket.dart"; +export "src/udp/rover_server.dart"; +export "src/udp/burt_protocol.dart"; +export "src/udp/rover_heartbeats.dart"; +export "src/udp/socket_info.dart"; +export "src/udp/udp_socket.dart"; + +export "src/serial/device.dart"; +export "src/serial/firmware.dart"; +export "src/serial/port_delegate.dart"; +export "src/serial/port_interface.dart"; + +export "src/service.dart"; export "generated.dart"; +export "logging.dart"; diff --git a/lib/logging.dart b/lib/logging.dart index 1e53ad92..5a7ac34b 100644 --- a/lib/logging.dart +++ b/lib/logging.dart @@ -3,7 +3,7 @@ library; import "dart:io"; import "package:burt_network/burt_network.dart"; -import "package:logger/logger.dart"; + export "package:logger/logger.dart"; /// An alias for [Level]. @@ -19,7 +19,15 @@ class BurtLogger { /// The device that's sending these logs. final Device? device; - final RoverServer? socket; + + /// The socket to send messages over. + /// + /// If this is not null, logs of type [Level.info] or more severe will be queued up. Once this + /// socket connects, the messages will send to the connected device (ie, the Dashboard). + /// + /// If the device is already connected, all messages are sent to it immediately. + RoverServer? socket; + /// Creates a logger capable of sending network messages over the given socket. BurtLogger({this.socket}) : device = socket?.device; diff --git a/lib/src/rover_server.dart b/lib/src/rover_server.dart deleted file mode 100644 index b7bccf3a..00000000 --- a/lib/src/rover_server.dart +++ /dev/null @@ -1,38 +0,0 @@ -import "dart:io"; -import "package:meta/meta.dart"; -import "package:burt_network/generated.dart"; - -import "rover_heartbeats.dart"; -import "burt_protocol.dart"; -import "rover_logger.dart"; -import "socket_info.dart"; - -abstract class RoverServer extends BurtUdpProtocol with RoverHeartbeats, RoverLogger { - RoverServer({ - required super.port, - required super.device, - super.quiet, - }); - - @override - void onWrapper(WrappedMessage wrapper, SocketInfo source) { - if (wrapper.name == UpdateSetting().messageName) { - final settings = UpdateSetting.fromBuffer(wrapper.data); - updateSettings(settings); - } - super.onWrapper(wrapper, source); - } - - @mustCallSuper - void updateSettings(UpdateSetting settings) { - sendMessage(settings); - if (settings.status == RoverStatus.POWER_OFF) { - logger.critical("Shutting down..."); - Process.run("sudo", ["shutdown", "now"]); - } else if (settings.status == RoverStatus.RESTART) { - restart(); - } - } - - void restart(); -} diff --git a/lib/src/serial/device.dart b/lib/src/serial/device.dart new file mode 100644 index 00000000..ca487040 --- /dev/null +++ b/lib/src/serial/device.dart @@ -0,0 +1,95 @@ +import "dart:async"; +import "dart:typed_data"; + +import "package:burt_network/burt_network.dart"; + +/// A wrapper around the `package:libserialport` library. +/// +/// - Check [DelegateSerialPort.allPorts] for a list of all available ports. +/// - Call [init] to open the port +/// - Use [write] to write bytes to the port. Strings are not supported +/// - Listen to [stream] to get incoming data +/// - Call [dispose] to close the port +class SerialDevice extends Service { + /// The port to connect to. + final String portName; + /// How often to read from the port. + final Duration readInterval; + /// The underlying connection to the serial port. + final SerialPortInterface _port; + /// The logger to use + final BurtLogger logger; + + /// A timer to periodically read from the port (see [readBytes]). + Timer? _timer; + + /// The controller for [stream]. + final _controller = StreamController.broadcast(); + + /// Manages a connection to a serial device. + SerialDevice({ + required this.portName, + required this.readInterval, + required this.logger, + }) : _port = SerialPortInterface.factory(portName); + + /// Whether the port is open (ie, the device is connected). + bool get isOpen => _port.isOpen; + + @override + Future init() async { + try { + return _port.init(); + } catch (error) { + return false; + } + } + + /// Starts listening to data sent over the serial port via [stream]. + void startListening() => _timer = Timer.periodic(readInterval, _listenForBytes); + + /// Stops listening to the serial port. + void stopListening() => _timer?.cancel(); + + /// Reads bytes from the port. If [count] is provided, only reads that number of bytes. + Uint8List readBytes([int? count]) { + try { + return _port.read(count ?? _port.bytesAvailable); + } catch (error) { + logger.error("Could not read from serial port $portName:\n $error"); + return Uint8List(0); + } + } + + /// Reads any data from the port and adds it to the [stream]. + void _listenForBytes(_) { + try { + final bytes = readBytes(); + if (bytes.isEmpty) return; + _controller.add(bytes); + } catch (error) { + logger.critical("Could not read $portName", body: error.toString()); + dispose(); + } + } + + @override + Future dispose() async { + _timer?.cancel(); + await _port.dispose(); + await _controller.close(); + } + + /// Writes data to the port. + void write(Uint8List data) { + if (!_port.isOpen) return; + try { + _port.write(data); + } catch (error) { + logger.warning("Could not write data to port $portName"); + } + } + + /// All incoming bytes coming from the port. + Stream get stream => _controller.stream; +} diff --git a/lib/src/serial/firmware.dart b/lib/src/serial/firmware.dart new file mode 100644 index 00000000..f5d8039a --- /dev/null +++ b/lib/src/serial/firmware.dart @@ -0,0 +1,101 @@ +import "dart:typed_data"; + +import "package:protobuf/protobuf.dart"; + +import "package:burt_network/burt_network.dart"; + +/// Represents a firmware device connected over Serial. +/// +/// This device starts with an unknown [device]. Calling [init] starts a handshake with the device +/// that identifies it. If the handshake fails, [isReady] will be false. Calling [dispose] will +/// reset the device and close the connection. +class BurtFirmwareSerial extends Service { + /// The interval to read serial data at. + static const readInterval = Duration(milliseconds: 100); + /// How long it should take for a firmware device to respond to a handshake. + static const handshakeDelay = Duration(milliseconds: 200); + /// The reset code to send to a firmware device. + static final resetCode = Uint8List.fromList([0, 0, 0, 0]); + + /// The name of this device. + Device device = Device.FIRMWARE; + + SerialDevice? _serial; + + /// The port this device is attached to. + final String port; + /// The logger to use. + final BurtLogger logger; + /// Creates a firmware device at the given serial port. + BurtFirmwareSerial({required this.port, required this.logger}); + + /// The stream of incoming data. + Stream? get stream => _serial?.stream; + + /// Whether this device has passed the handshake. + bool get isReady => device != Device.FIRMWARE; + + @override + Future init() async { + // Open the port + _serial = SerialDevice(portName: port, readInterval: readInterval, logger: logger); + if (!await _serial!.init()) { + logger.warning("Could not open firmware device on port $port"); + return false; + } + + // Execute the handshake + if (!_reset()) logger.warning("The Teensy on port $port failed to reset"); + if (!await _sendHandshake()) { + logger.warning("Could not connect to Teensy", body: "Device on port $port failed the handshake"); + return false; + } + + logger.info("Connected to the ${device.name} Teensy on port $port"); + _serial!.startListening(); + return true; + } + + /// Sends the handshake to the device and returns whether it was successful. + Future _sendHandshake() async { + logger.debug("Sending handshake to port $port..."); + final handshake = Connect(sender: Device.SUBSYSTEMS, receiver: Device.FIRMWARE); + _serial!.write(handshake.writeToBuffer()); + await Future.delayed(handshakeDelay); + final response = _serial!.readBytes(4); + if (response.isEmpty) { + logger.trace("Device did not respond"); + return false; + } + try { + final message = Connect.fromBuffer(response); + logger.trace("Device responded with: ${message.toProto3Json()}"); + if (message.receiver != Device.SUBSYSTEMS) return false; + device = message.sender; + return true; + } on InvalidProtocolBufferException { + logger.trace("Device responded with malformed data: $response"); + return false; + } + } + + /// Sends the reset code and returns whether the device confirmed its reset. + bool _reset() { + _serial?.write(resetCode); + final response = _serial?.readBytes( 4); + if (response == null) return false; + if (response.length != 4 || response.any((x) => x != 1)) return false; + logger.info("The ${device.name} Teensy has been reset"); + return true; + } + + /// Sends bytes to the device via Serial. + void sendBytes(List bytes) => _serial?.write(Uint8List.fromList(bytes)); + + /// Resets the device and closes the port. + @override + Future dispose() async { + if (!_reset()) logger.warning("The $device device on port $port did not reset"); + await _serial?.dispose(); + } +} diff --git a/lib/src/serial/port_delegate.dart b/lib/src/serial/port_delegate.dart new file mode 100644 index 00000000..f0258593 --- /dev/null +++ b/lib/src/serial/port_delegate.dart @@ -0,0 +1,45 @@ +import "dart:typed_data"; + +import "package:libserialport/libserialport.dart"; + +import "port_interface.dart"; + +/// A serial port implementation that delegates to [`package:libserialport`](https://pub.dev/packages/libserialport) +class DelegateSerialPort extends SerialPortInterface { + /// A list of all available ports on the device. + static List allPorts = SerialPort.availablePorts; + + SerialPort? _delegate; + + /// Creates a serial port that delegates to the `libserialport` package. + DelegateSerialPort(super.portName); + + @override + bool get isOpen => _delegate?.isOpen ?? false; + + @override + Future init() async { + try { + _delegate = SerialPort(portName); + return _delegate!.openReadWrite(); + } catch (error) { + return false; + } + } + + @override + int get bytesAvailable => _delegate?.bytesAvailable ?? 0; + + @override + Uint8List read(int count) => _delegate?.read(count) ?? Uint8List.fromList([]); + + @override + void write(Uint8List bytes) => _delegate?.write(bytes); + + @override + Future dispose() async { + if (!isOpen) return; + _delegate?.close(); + _delegate?.dispose(); + } +} diff --git a/lib/src/serial/port_interface.dart b/lib/src/serial/port_interface.dart new file mode 100644 index 00000000..532bfba2 --- /dev/null +++ b/lib/src/serial/port_interface.dart @@ -0,0 +1,29 @@ +import "dart:typed_data"; + +import "package:burt_network/burt_network.dart"; + +export "port_delegate.dart"; + +/// An interface to a serial port. +abstract class SerialPortInterface extends Service { + /// The default kind of port to create. Use this when mocking with different ports. + static SerialPortInterface Function(String) factory = DelegateSerialPort.new; + + /// The name of the port. + final String portName; + + /// Creates a serial port at the given name. + SerialPortInterface(this.portName); + + /// Whether this port is open. + bool get isOpen; + + /// How many bytes are available to be read. + int get bytesAvailable; + + /// Reads the given number of bytes from the port. + Uint8List read(int count); + + /// Writes data to the port. + void write(Uint8List bytes); +} diff --git a/lib/src/service.dart b/lib/src/service.dart new file mode 100644 index 00000000..4b05f979 --- /dev/null +++ b/lib/src/service.dart @@ -0,0 +1,12 @@ +import "package:meta/meta.dart"; + +/// A class that represents a connection to some other API, service, or device. +abstract class Service { + /// Initializes the connection to the device. + @mustCallSuper + Future init(); + + /// Closes the connection to the device. + @mustCallSuper + Future dispose(); +} diff --git a/lib/src/burt_protocol.dart b/lib/src/udp/burt_protocol.dart similarity index 51% rename from lib/src/burt_protocol.dart rename to lib/src/udp/burt_protocol.dart index e6694886..29b18156 100644 --- a/lib/src/burt_protocol.dart +++ b/lib/src/udp/burt_protocol.dart @@ -6,6 +6,16 @@ import "dart:async"; import "proto_socket.dart"; import "socket_info.dart"; +/// A UDP socket that implements the BURT communication protocol. +/// +/// The protocol ensures devices connect by sending a [Connect] message to initiate a handshake. +/// This process is repeated periodically to create "heartbeats" that indicate the status of the +/// connection. +/// +/// - Override [isConnected] to indicate when this socket has successfully connected. +/// - Override [checkHeartbeats] to tell the socket how to check for incoming heartbeats. +/// - Override [onHeartbeat] to be notified of an incoming heartbeat. +/// - Override [onMessage] to be notified of a non-heartbeat message. abstract class BurtUdpProtocol extends ProtoSocket { /// A timer to call [checkHeartbeats] every [heartbeatInterval]. Timer? heartbeatTimer; @@ -13,6 +23,7 @@ abstract class BurtUdpProtocol extends ProtoSocket { /// How often to check for heartbeats. Duration get heartbeatInterval; + /// Creates a UDP socket that implements the BURT communication protocols. BurtUdpProtocol({ required super.port, required super.device, @@ -42,8 +53,15 @@ abstract class BurtUdpProtocol extends ProtoSocket { } } + /// Whether the socket is connected to the intended device(s). bool get isConnected; + /// Checks for incoming heartbeats from the intended device(s). + /// + /// For example, on the rover, this waits for new heartbeats, but on the Dashboard, + /// it sends heartbeats to every connected device. void checkHeartbeats(); + /// Handles an incoming heartbeat from another device. void onHeartbeat(Connect heartbeat, SocketInfo source); + /// Handles a non-heartbeat message, usually containing data or commands. void onMessage(WrappedMessage wrapper); } diff --git a/lib/src/proto_socket.dart b/lib/src/udp/proto_socket.dart similarity index 80% rename from lib/src/proto_socket.dart rename to lib/src/udp/proto_socket.dart index cbe60eee..b81df290 100644 --- a/lib/src/proto_socket.dart +++ b/lib/src/udp/proto_socket.dart @@ -5,9 +5,12 @@ import "package:burt_network/generated.dart"; import "socket_info.dart"; import "udp_socket.dart"; +/// A [UdpSocket] that speaks in Protobuf [Message]s, not bytes abstract class ProtoSocket extends UdpSocket { + /// The rover device this socket represents. final Device device; + /// Creates a new UDP socket that uses Protobuf. ProtoSocket({ required this.device, required super.port, @@ -27,8 +30,10 @@ abstract class ProtoSocket extends UdpSocket { void sendWrapper(WrappedMessage wrapper, {SocketInfo? destinationOverride}) => sendData(wrapper.writeToBuffer(), destinationOverride: destinationOverride); + /// Wraps a message and sends it with [sendWrapper]. void sendMessage(Message message, {SocketInfo? destinationOverride}) => sendWrapper(message.wrap(), destinationOverride: destinationOverride); + /// A callback for when messages are received. void onWrapper(WrappedMessage wrapper, SocketInfo source); } diff --git a/lib/src/rover_heartbeats.dart b/lib/src/udp/rover_heartbeats.dart similarity index 96% rename from lib/src/rover_heartbeats.dart rename to lib/src/udp/rover_heartbeats.dart index 12e9f2cc..cddb2d6a 100644 --- a/lib/src/rover_heartbeats.dart +++ b/lib/src/udp/rover_heartbeats.dart @@ -5,6 +5,7 @@ import "package:burt_network/generated.dart"; import "burt_protocol.dart"; import "socket_info.dart"; +/// A mixin that automatically handles rover-side heartbeats. mixin RoverHeartbeats on BurtUdpProtocol { /// Whether this socket received a heartbeat since the last call to [checkHeartbeats]. bool didReceivedHeartbeat = false; @@ -50,6 +51,7 @@ mixin RoverHeartbeats on BurtUdpProtocol { } } + /// Responds to an incoming heartbeat. void sendHeartbeatResponse() { final response = Connect(sender: device, receiver: Device.DASHBOARD); sendMessage(response); diff --git a/lib/src/rover_logger.dart b/lib/src/udp/rover_logger.dart similarity index 82% rename from lib/src/rover_logger.dart rename to lib/src/udp/rover_logger.dart index 7447657b..c8290045 100644 --- a/lib/src/rover_logger.dart +++ b/lib/src/udp/rover_logger.dart @@ -3,6 +3,10 @@ import "package:burt_network/generated.dart"; import "rover_heartbeats.dart"; import "socket_info.dart"; +/// A socket that can log messages using [sendLog]. +/// +/// If connected, this socket will send log messages immediately. If not, it will hold onto +/// messages and send them when the device finally connects. mixin RoverLogger on RoverHeartbeats { /// A list of important logs that need to be sent when the dashboard connects. final List _logBuffer = []; diff --git a/lib/src/udp/rover_server.dart b/lib/src/udp/rover_server.dart new file mode 100644 index 00000000..eb8cf5d5 --- /dev/null +++ b/lib/src/udp/rover_server.dart @@ -0,0 +1,8 @@ +import "burt_protocol.dart"; + +import "rover_heartbeats.dart"; +import "rover_logger.dart"; +import "rover_settings.dart"; + +/// A UDP socket fit for use on the rover, with heartbeats, logging, and settings included. +abstract class RoverServer = BurtUdpProtocol with RoverHeartbeats, RoverLogger, RoverSettings; diff --git a/lib/src/udp/rover_settings.dart b/lib/src/udp/rover_settings.dart new file mode 100644 index 00000000..6aae5080 --- /dev/null +++ b/lib/src/udp/rover_settings.dart @@ -0,0 +1,50 @@ +import "dart:io"; + +import "package:meta/meta.dart"; +import "package:burt_network/generated.dart"; + +import "socket_info.dart"; +import "burt_protocol.dart"; + +/// A mixin that handles [UpdateSetting] commands. +mixin RoverSettings on BurtUdpProtocol { + @override + void onWrapper(WrappedMessage wrapper, SocketInfo source) { + if (wrapper.name == UpdateSetting().messageName) { + final settings = UpdateSetting.fromBuffer(wrapper.data); + updateSettings(settings); + } else { + super.onWrapper(wrapper, source); + } + } + + /// Handles an [UpdateSetting] command and updates the appropriate setting. + /// + /// Also sends a handshake response to indicate the message was received. + @mustCallSuper + Future updateSettings(UpdateSetting settings) async { + sendMessage(settings); + if (settings.status == RoverStatus.POWER_OFF) { + logger.critical("Shutting down..."); + try { + await onShutdown().timeout(const Duration(seconds: 5)); + } catch (error) { + logger.critical("Error when shutting down: $error"); + } + if (!Platform.isLinux) exit(0); + await Process.run("sudo", ["shutdown", "now"]); + } else if (settings.status == RoverStatus.RESTART) { + await restart(); + } + } + + /// Restarts this program, usually by disposing and re-initializing the collection. + Future restart(); + + /// Shuts down the program by disposing the collection. + /// + /// This gives any other parts of the rover a chance to shut down as well. For example, + /// if the Subsystems program shuts down, the drive firmware would continue out of control. + /// Overriding this function gives it the chance to stop the firmware first. + Future onShutdown(); +} diff --git a/lib/src/socket_info.dart b/lib/src/udp/socket_info.dart similarity index 100% rename from lib/src/socket_info.dart rename to lib/src/udp/socket_info.dart diff --git a/lib/src/udp_socket.dart b/lib/src/udp/udp_socket.dart similarity index 93% rename from lib/src/udp_socket.dart rename to lib/src/udp/udp_socket.dart index 7718ea64..772a7d52 100644 --- a/lib/src/udp_socket.dart +++ b/lib/src/udp/udp_socket.dart @@ -20,6 +20,7 @@ abstract class UdpSocket { /// A collection of allowed [OSError] codes. static const allowedErrors = {1234, 10054, 101, 10038, 9}; + /// A logger to capture important events during operation. final logger = BurtLogger(); /// Whether to silence "normal" output, like opening/closing and resetting sockets. @@ -28,6 +29,10 @@ abstract class UdpSocket { /// The port this socket is listening on. See [RawDatagramSocket.bind]. int? port; + /// The destination port to send to. + /// + /// All the `send*` functions allow you to send to a specific [SocketInfo]. This field + /// is the default destination if those parameters are omitted. SocketInfo? destination; /// Opens a UDP socket on the given port that can send and receive data. diff --git a/pubspec.yaml b/pubspec.yaml index 985675df..94f97f0a 100644 --- a/pubspec.yaml +++ b/pubspec.yaml @@ -4,10 +4,11 @@ version: 1.1.0 # repository: https://github.com/my_org/my_repo environment: - sdk: ^3.0.0 + sdk: 3.2.2 # Add regular dependencies here. dependencies: + libserialport: ^0.3.0+1 logger: ^2.0.2 meta: ^1.9.1 protobuf: ^3.0.0 diff --git a/test/failing_port.dart b/test/failing_port.dart new file mode 100644 index 00000000..4203a2cf --- /dev/null +++ b/test/failing_port.dart @@ -0,0 +1,16 @@ +import "dart:typed_data"; + +import "package:burt_network/burt_network.dart"; + +class FailingSerialPort extends SerialPortInterface { + FailingSerialPort(super.portName); + + @override bool get isOpen => false; + @override int get bytesAvailable => 0; + + @override Future init() => throw UnsupportedError("Test port cannot open"); + @override Uint8List read(int count) => throw UnsupportedError("Test port cannot read"); + + @override Future dispose() async { } + @override bool write(Uint8List bytes) => throw UnsupportedError("Test port cannot write"); +} diff --git a/test/proto_test.dart b/test/proto_test.dart index 476a956f..85adc162 100644 --- a/test/proto_test.dart +++ b/test/proto_test.dart @@ -1,6 +1,5 @@ import "dart:io"; import "package:burt_network/burt_network.dart"; -import "package:burt_network/logging.dart"; import "package:test/test.dart"; final address = InternetAddress.loopbackIPv4; @@ -25,22 +24,33 @@ void main() => group("ProtoSocket:", () { }); test("Heartbeats received by both client and server", () async { - await Future.delayed(const Duration(seconds: 3)); + await Future.delayed(const Duration(milliseconds: 50)); expect(server.isConnected, isTrue); expect(client.isConnected, isTrue); }); test("onConnect and onDisconnect are called", () async { - client.shouldSendHeartbeats = false; - await Future.delayed(const Duration(seconds: 3)); - expect(server.onConnectCalled, isTrue); - expect(server.onDisconnectCalled, isTrue); + final serverInfo = SocketInfo(port: 8002, address: InternetAddress.loopbackIPv4); + final clientInfo = SocketInfo(port: 8003, address: InternetAddress.loopbackIPv4); + final server2 = TestServer(port: serverInfo.port, device: Device.SUBSYSTEMS); + final client2 = TestClient(port: clientInfo.port, device: Device.DASHBOARD); + client2.destination = serverInfo; + await server2.init(); + await client2.init(); + client2.shouldSendHeartbeats = true; + await Future.delayed(const Duration(milliseconds: 50)); + expect(server2.onConnectCalled, isTrue); + client2.shouldSendHeartbeats = false; + await Future.delayed(const Duration(milliseconds: 50)); + expect(server2.onDisconnectCalled, isTrue); + await server2.dispose(); + await client2.dispose(); }); test("Data makes it across", () async { final data = ScienceData(methane: 3); client.sendMessage(data); - await Future.delayed(const Duration(seconds: 1)); + await Future.delayed(const Duration(milliseconds: 50)); expect(server.data, equals(data)); }); @@ -50,13 +60,16 @@ void main() => group("ProtoSocket:", () { }); }); -class TestServer extends BurtUdpProtocol with RoverHeartbeats { +class TestServer extends RoverServer { ScienceData? data; bool onConnectCalled = false; bool onDisconnectCalled = false; TestServer({required super.port, required super.device}); + @override + Duration get heartbeatInterval => const Duration(milliseconds: 10); + @override void onMessage(WrappedMessage wrapper) => data = ScienceData.fromBuffer(wrapper.data); @@ -71,11 +84,17 @@ class TestServer extends BurtUdpProtocol with RoverHeartbeats { super.onDisconnect(); onDisconnectCalled = true; } + + @override + Future onShutdown() async { } + + @override + Future restart() async { } } class TestClient extends BurtUdpProtocol { @override - Duration get heartbeatInterval => const Duration(seconds: 1); + Duration get heartbeatInterval => const Duration(milliseconds: 10); TestClient({required super.port, required super.device}); diff --git a/test/serial_device_mock_test.dart b/test/serial_device_mock_test.dart new file mode 100644 index 00000000..aab00199 --- /dev/null +++ b/test/serial_device_mock_test.dart @@ -0,0 +1,55 @@ +import "dart:typed_data"; + +import "package:burt_network/burt_network.dart"; +import "package:test/test.dart"; + +void main() { + Logger.level = LogLevel.off; + final logger = BurtLogger(); + + group("Disconnected Serial device", () { + const readInterval = Duration(milliseconds: 100); + final device = SerialDevice(logger: logger, portName: "port", readInterval: readInterval); + setUp(device.init); + tearDownAll(device.dispose); + + test("reports when a device is not connected", () async { + final device2 = SerialDevice(logger: logger, portName: "port", readInterval: readInterval); + final result = await device2.init(); + expect(result, isFalse); + }); + + test("reads nothing", () { + final data1 = device.readBytes(); + expect(data1, isEmpty); + final data2 = device.readBytes(10); + expect(data2, isEmpty); + }); + + test("streams nothing", () async { + device.stream.listen(neverCalled); + device.startListening(); + await Future.delayed(const Duration(seconds: 1)); + device.stopListening(); + }); + + test("does not error on write", () async { + const data = [1, 2, 3, 4, 5, 6, 7, 8]; + final bytes = Uint8List.fromList(data); + void func() => device.write(bytes); + expect(func, returnsNormally); + }); + + test("only closes its stream on dispose", () async { + // Someone may call [stopListening] at any time. + // This will detach any other listeners, if there are any. + var count = 0; + device.stream.listen(neverCalled, onDone: () => count++); + device.startListening(); + device.stopListening(); + await device.dispose(); + expect(device.stream, emitsDone); + expect(count, 1); + }); + }); +} diff --git a/test/serial_port_fail_test.dart b/test/serial_port_fail_test.dart new file mode 100644 index 00000000..2976db2d --- /dev/null +++ b/test/serial_port_fail_test.dart @@ -0,0 +1,52 @@ +import "dart:typed_data"; +import "package:test/test.dart"; + +import "package:burt_network/burt_network.dart"; + +import "failing_port.dart"; + +const readInterval = Duration(milliseconds: 100); + +void main() async { + Logger.level = LogLevel.off; + final logger = BurtLogger(); + SerialPortInterface.factory = FailingSerialPort.new; + final device = SerialDevice(logger: logger, portName: "portName", readInterval: readInterval); + SerialPortInterface.factory = DelegateSerialPort.new; + + group("Failing Serial port", () { + setUp(device.init); + tearDown(device.dispose); + + test("can safely restart", () async { + await device.dispose(); + await device.init(); + }); + + test("reports errors when opening", () async { + await device.dispose(); + final result = await device.init(); + expect(result, isFalse); + }); + + test("handles errors when listening", () async { + device.startListening(); + const listenDelay = Duration(seconds: 1); + await Future.delayed(listenDelay); + device.stopListening(); + }); + + test("handles errors when reading", () { + final bytes1 = device.readBytes(); + expect(bytes1, isEmpty); + final bytes2 = device.readBytes(10); + expect(bytes2, isEmpty); + }); + + test("handles errors when writing", () { + const data = [1, 2, 3, 4, 5, 6, 7, 8]; + final buffer = Uint8List.fromList(data); + device.write(buffer); + }); + }); +}