From d6ce255cd28a3313f02275c782b77f04603b0489 Mon Sep 17 00:00:00 2001 From: Levi Lesches Date: Mon, 27 Feb 2023 14:18:13 -0500 Subject: [PATCH] Control the Arm (#66) Controls the arm and adds a list of controls to the UI Closes #53 --- lib/data.dart | 1 + lib/src/data/Protobuf | 2 +- lib/src/data/generated/arm.pb.dart | 516 +++++++--------------- lib/src/data/generated/arm.pbjson.dart | 74 +--- lib/src/models/data/home.dart | 15 +- lib/src/models/data/video.dart | 2 +- lib/src/models/rover/arm.dart | 41 ++ lib/src/models/rover/controller.dart | 18 +- lib/src/models/rover/core.dart | 4 +- lib/src/models/rover/drive.dart | 28 +- lib/src/models/rover/stub.dart | 3 + lib/src/pages/home.dart | 119 +++-- lib/src/services/gamepad.dart | 31 +- lib/src/widgets/atomic/video_feed.dart | 80 ++-- lib/src/widgets/generic/metrics_list.dart | 3 +- lib/src/widgets/navigation/sidebar.dart | 10 +- 16 files changed, 454 insertions(+), 493 deletions(-) create mode 100644 lib/src/models/rover/arm.dart diff --git a/lib/data.dart b/lib/data.dart index ac33ec711..68772cca0 100644 --- a/lib/data.dart +++ b/lib/data.dart @@ -10,6 +10,7 @@ /// library should import any other library. library data; +export "src/data/generated/arm.pb.dart"; export "src/data/generated/core.pb.dart"; export "src/data/generated/drive.pb.dart"; export "src/data/generated/electrical.pb.dart"; diff --git a/lib/src/data/Protobuf b/lib/src/data/Protobuf index 90b2031b3..96634321d 160000 --- a/lib/src/data/Protobuf +++ b/lib/src/data/Protobuf @@ -1 +1 @@ -Subproject commit 90b2031b3df1e1cbcaa70feaedb299307f4f3f0e +Subproject commit 96634321de51c54936537fa7888982cbfcfeb1a2 diff --git a/lib/src/data/generated/arm.pb.dart b/lib/src/data/generated/arm.pb.dart index c2822a91b..fd48e3791 100644 --- a/lib/src/data/generated/arm.pb.dart +++ b/lib/src/data/generated/arm.pb.dart @@ -84,153 +84,6 @@ class Position extends $pb.GeneratedMessage { void clearZ() => clearField(3); } -class ArmCommand extends $pb.GeneratedMessage { - static final $pb.BuilderInfo _i = $pb.BuilderInfo(const $core.bool.fromEnvironment('protobuf.omit_message_names') ? '' : 'ArmCommand', createEmptyInstance: create) - ..aOM(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'moveTo', subBuilder: Position.create) - ..aOB(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'calibrate') - ..a<$core.double>(3, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'swivel', $pb.PbFieldType.OF) - ..a<$core.double>(4, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'extend', $pb.PbFieldType.OF) - ..a<$core.double>(5, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'lift', $pb.PbFieldType.OF) - ..a<$core.double>(6, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'preciseSwivel', $pb.PbFieldType.OF) - ..a<$core.double>(7, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'preciseLift', $pb.PbFieldType.OF) - ..a<$core.double>(8, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'preciseExtend', $pb.PbFieldType.OF) - ..hasRequiredFields = false - ; - - ArmCommand._() : super(); - factory ArmCommand({ - Position? moveTo, - $core.bool? calibrate, - $core.double? swivel, - $core.double? extend, - $core.double? lift, - $core.double? preciseSwivel, - $core.double? preciseLift, - $core.double? preciseExtend, - }) { - final _result = create(); - if (moveTo != null) { - _result.moveTo = moveTo; - } - if (calibrate != null) { - _result.calibrate = calibrate; - } - if (swivel != null) { - _result.swivel = swivel; - } - if (extend != null) { - _result.extend = extend; - } - if (lift != null) { - _result.lift = lift; - } - if (preciseSwivel != null) { - _result.preciseSwivel = preciseSwivel; - } - if (preciseLift != null) { - _result.preciseLift = preciseLift; - } - if (preciseExtend != null) { - _result.preciseExtend = preciseExtend; - } - return _result; - } - factory ArmCommand.fromBuffer($core.List<$core.int> i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromBuffer(i, r); - factory ArmCommand.fromJson($core.String i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromJson(i, r); - @$core.Deprecated( - 'Using this can add significant overhead to your binary. ' - 'Use [GeneratedMessageGenericExtensions.deepCopy] instead. ' - 'Will be removed in next major version') - ArmCommand clone() => ArmCommand()..mergeFromMessage(this); - @$core.Deprecated( - 'Using this can add significant overhead to your binary. ' - 'Use [GeneratedMessageGenericExtensions.rebuild] instead. ' - 'Will be removed in next major version') - ArmCommand copyWith(void Function(ArmCommand) updates) => super.copyWith((message) => updates(message as ArmCommand)) as ArmCommand; // ignore: deprecated_member_use - $pb.BuilderInfo get info_ => _i; - @$core.pragma('dart2js:noInline') - static ArmCommand create() => ArmCommand._(); - ArmCommand createEmptyInstance() => create(); - static $pb.PbList createRepeated() => $pb.PbList(); - @$core.pragma('dart2js:noInline') - static ArmCommand getDefault() => _defaultInstance ??= $pb.GeneratedMessage.$_defaultFor(create); - static ArmCommand? _defaultInstance; - - @$pb.TagNumber(1) - Position get moveTo => $_getN(0); - @$pb.TagNumber(1) - set moveTo(Position v) { setField(1, v); } - @$pb.TagNumber(1) - $core.bool hasMoveTo() => $_has(0); - @$pb.TagNumber(1) - void clearMoveTo() => clearField(1); - @$pb.TagNumber(1) - Position ensureMoveTo() => $_ensure(0); - - @$pb.TagNumber(2) - $core.bool get calibrate => $_getBF(1); - @$pb.TagNumber(2) - set calibrate($core.bool v) { $_setBool(1, v); } - @$pb.TagNumber(2) - $core.bool hasCalibrate() => $_has(1); - @$pb.TagNumber(2) - void clearCalibrate() => clearField(2); - - @$pb.TagNumber(3) - $core.double get swivel => $_getN(2); - @$pb.TagNumber(3) - set swivel($core.double v) { $_setFloat(2, v); } - @$pb.TagNumber(3) - $core.bool hasSwivel() => $_has(2); - @$pb.TagNumber(3) - void clearSwivel() => clearField(3); - - @$pb.TagNumber(4) - $core.double get extend => $_getN(3); - @$pb.TagNumber(4) - set extend($core.double v) { $_setFloat(3, v); } - @$pb.TagNumber(4) - $core.bool hasExtend() => $_has(3); - @$pb.TagNumber(4) - void clearExtend() => clearField(4); - - @$pb.TagNumber(5) - $core.double get lift => $_getN(4); - @$pb.TagNumber(5) - set lift($core.double v) { $_setFloat(4, v); } - @$pb.TagNumber(5) - $core.bool hasLift() => $_has(4); - @$pb.TagNumber(5) - void clearLift() => clearField(5); - - @$pb.TagNumber(6) - $core.double get preciseSwivel => $_getN(5); - @$pb.TagNumber(6) - set preciseSwivel($core.double v) { $_setFloat(5, v); } - @$pb.TagNumber(6) - $core.bool hasPreciseSwivel() => $_has(5); - @$pb.TagNumber(6) - void clearPreciseSwivel() => clearField(6); - - @$pb.TagNumber(7) - $core.double get preciseLift => $_getN(6); - @$pb.TagNumber(7) - set preciseLift($core.double v) { $_setFloat(6, v); } - @$pb.TagNumber(7) - $core.bool hasPreciseLift() => $_has(6); - @$pb.TagNumber(7) - void clearPreciseLift() => clearField(7); - - @$pb.TagNumber(8) - $core.double get preciseExtend => $_getN(7); - @$pb.TagNumber(8) - set preciseExtend($core.double v) { $_setFloat(7, v); } - @$pb.TagNumber(8) - $core.bool hasPreciseExtend() => $_has(7); - @$pb.TagNumber(8) - void clearPreciseExtend() => clearField(8); -} - class MotorStatus extends $pb.GeneratedMessage { static final $pb.BuilderInfo _i = $pb.BuilderInfo(const $core.bool.fromEnvironment('protobuf.omit_message_names') ? '' : 'MotorStatus', createEmptyInstance: create) ..aOB(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'isMoving') @@ -419,35 +272,133 @@ class ArmData extends $pb.GeneratedMessage { MotorStatus ensureElbow() => $_ensure(4); } +class ArmCommand extends $pb.GeneratedMessage { + static final $pb.BuilderInfo _i = $pb.BuilderInfo(const $core.bool.fromEnvironment('protobuf.omit_message_names') ? '' : 'ArmCommand', createEmptyInstance: create) + ..aOB(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'stop') + ..aOB(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'calibrate') + ..a<$core.double>(3, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'moveSwivel', $pb.PbFieldType.OF) + ..a<$core.double>(4, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'moveShoulder', $pb.PbFieldType.OF) + ..a<$core.double>(5, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'moveElbow', $pb.PbFieldType.OF) + ..hasRequiredFields = false + ; + + ArmCommand._() : super(); + factory ArmCommand({ + $core.bool? stop, + $core.bool? calibrate, + $core.double? moveSwivel, + $core.double? moveShoulder, + $core.double? moveElbow, + }) { + final _result = create(); + if (stop != null) { + _result.stop = stop; + } + if (calibrate != null) { + _result.calibrate = calibrate; + } + if (moveSwivel != null) { + _result.moveSwivel = moveSwivel; + } + if (moveShoulder != null) { + _result.moveShoulder = moveShoulder; + } + if (moveElbow != null) { + _result.moveElbow = moveElbow; + } + return _result; + } + factory ArmCommand.fromBuffer($core.List<$core.int> i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromBuffer(i, r); + factory ArmCommand.fromJson($core.String i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromJson(i, r); + @$core.Deprecated( + 'Using this can add significant overhead to your binary. ' + 'Use [GeneratedMessageGenericExtensions.deepCopy] instead. ' + 'Will be removed in next major version') + ArmCommand clone() => ArmCommand()..mergeFromMessage(this); + @$core.Deprecated( + 'Using this can add significant overhead to your binary. ' + 'Use [GeneratedMessageGenericExtensions.rebuild] instead. ' + 'Will be removed in next major version') + ArmCommand copyWith(void Function(ArmCommand) updates) => super.copyWith((message) => updates(message as ArmCommand)) as ArmCommand; // ignore: deprecated_member_use + $pb.BuilderInfo get info_ => _i; + @$core.pragma('dart2js:noInline') + static ArmCommand create() => ArmCommand._(); + ArmCommand createEmptyInstance() => create(); + static $pb.PbList createRepeated() => $pb.PbList(); + @$core.pragma('dart2js:noInline') + static ArmCommand getDefault() => _defaultInstance ??= $pb.GeneratedMessage.$_defaultFor(create); + static ArmCommand? _defaultInstance; + + @$pb.TagNumber(1) + $core.bool get stop => $_getBF(0); + @$pb.TagNumber(1) + set stop($core.bool v) { $_setBool(0, v); } + @$pb.TagNumber(1) + $core.bool hasStop() => $_has(0); + @$pb.TagNumber(1) + void clearStop() => clearField(1); + + @$pb.TagNumber(2) + $core.bool get calibrate => $_getBF(1); + @$pb.TagNumber(2) + set calibrate($core.bool v) { $_setBool(1, v); } + @$pb.TagNumber(2) + $core.bool hasCalibrate() => $_has(1); + @$pb.TagNumber(2) + void clearCalibrate() => clearField(2); + + @$pb.TagNumber(3) + $core.double get moveSwivel => $_getN(2); + @$pb.TagNumber(3) + set moveSwivel($core.double v) { $_setFloat(2, v); } + @$pb.TagNumber(3) + $core.bool hasMoveSwivel() => $_has(2); + @$pb.TagNumber(3) + void clearMoveSwivel() => clearField(3); + + @$pb.TagNumber(4) + $core.double get moveShoulder => $_getN(3); + @$pb.TagNumber(4) + set moveShoulder($core.double v) { $_setFloat(3, v); } + @$pb.TagNumber(4) + $core.bool hasMoveShoulder() => $_has(3); + @$pb.TagNumber(4) + void clearMoveShoulder() => clearField(4); + + @$pb.TagNumber(5) + $core.double get moveElbow => $_getN(4); + @$pb.TagNumber(5) + set moveElbow($core.double v) { $_setFloat(4, v); } + @$pb.TagNumber(5) + $core.bool hasMoveElbow() => $_has(4); + @$pb.TagNumber(5) + void clearMoveElbow() => clearField(5); +} + class GripperData extends $pb.GeneratedMessage { static final $pb.BuilderInfo _i = $pb.BuilderInfo(const $core.bool.fromEnvironment('protobuf.omit_message_names') ? '' : 'GripperData', createEmptyInstance: create) - ..a<$core.double>(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'rotation', $pb.PbFieldType.OF) - ..a<$core.double>(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'swivel', $pb.PbFieldType.OF) - ..a<$core.double>(3, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'pinch', $pb.PbFieldType.OF) - ..a<$core.double>(4, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'motorTemperature', $pb.PbFieldType.OF) + ..aOM(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'rotate', subBuilder: MotorStatus.create) + ..aOM(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'lift', subBuilder: MotorStatus.create) + ..aOM(3, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'pinch', subBuilder: MotorStatus.create) ..hasRequiredFields = false ; GripperData._() : super(); factory GripperData({ - $core.double? rotation, - $core.double? swivel, - $core.double? pinch, - $core.double? motorTemperature, + MotorStatus? rotate, + MotorStatus? lift, + MotorStatus? pinch, }) { final _result = create(); - if (rotation != null) { - _result.rotation = rotation; + if (rotate != null) { + _result.rotate = rotate; } - if (swivel != null) { - _result.swivel = swivel; + if (lift != null) { + _result.lift = lift; } if (pinch != null) { _result.pinch = pinch; } - if (motorTemperature != null) { - _result.motorTemperature = motorTemperature; - } return _result; } factory GripperData.fromBuffer($core.List<$core.int> i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromBuffer(i, r); @@ -472,75 +423,72 @@ class GripperData extends $pb.GeneratedMessage { static GripperData? _defaultInstance; @$pb.TagNumber(1) - $core.double get rotation => $_getN(0); + MotorStatus get rotate => $_getN(0); + @$pb.TagNumber(1) + set rotate(MotorStatus v) { setField(1, v); } @$pb.TagNumber(1) - set rotation($core.double v) { $_setFloat(0, v); } + $core.bool hasRotate() => $_has(0); @$pb.TagNumber(1) - $core.bool hasRotation() => $_has(0); + void clearRotate() => clearField(1); @$pb.TagNumber(1) - void clearRotation() => clearField(1); + MotorStatus ensureRotate() => $_ensure(0); @$pb.TagNumber(2) - $core.double get swivel => $_getN(1); + MotorStatus get lift => $_getN(1); @$pb.TagNumber(2) - set swivel($core.double v) { $_setFloat(1, v); } + set lift(MotorStatus v) { setField(2, v); } @$pb.TagNumber(2) - $core.bool hasSwivel() => $_has(1); + $core.bool hasLift() => $_has(1); @$pb.TagNumber(2) - void clearSwivel() => clearField(2); + void clearLift() => clearField(2); + @$pb.TagNumber(2) + MotorStatus ensureLift() => $_ensure(1); @$pb.TagNumber(3) - $core.double get pinch => $_getN(2); + MotorStatus get pinch => $_getN(2); @$pb.TagNumber(3) - set pinch($core.double v) { $_setFloat(2, v); } + set pinch(MotorStatus v) { setField(3, v); } @$pb.TagNumber(3) $core.bool hasPinch() => $_has(2); @$pb.TagNumber(3) void clearPinch() => clearField(3); - - @$pb.TagNumber(4) - $core.double get motorTemperature => $_getN(3); - @$pb.TagNumber(4) - set motorTemperature($core.double v) { $_setFloat(3, v); } - @$pb.TagNumber(4) - $core.bool hasMotorTemperature() => $_has(3); - @$pb.TagNumber(4) - void clearMotorTemperature() => clearField(4); + @$pb.TagNumber(3) + MotorStatus ensurePinch() => $_ensure(2); } class GripperCommand extends $pb.GeneratedMessage { static final $pb.BuilderInfo _i = $pb.BuilderInfo(const $core.bool.fromEnvironment('protobuf.omit_message_names') ? '' : 'GripperCommand', createEmptyInstance: create) - ..aOB(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'calibrate') - ..a<$core.double>(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'pinch', $pb.PbFieldType.OF) - ..a<$core.double>(3, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'rotate', $pb.PbFieldType.OF) - ..a<$core.double>(4, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'precisePinch', $pb.PbFieldType.OF) - ..a<$core.double>(5, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'preciseRotate', $pb.PbFieldType.OF) + ..aOB(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'stop') + ..aOB(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'calibrate') + ..a<$core.double>(3, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'moveRotate', $pb.PbFieldType.OF) + ..a<$core.double>(4, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'moveLift', $pb.PbFieldType.OF) + ..a<$core.double>(5, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'moveGripper', $pb.PbFieldType.OF) ..hasRequiredFields = false ; GripperCommand._() : super(); factory GripperCommand({ + $core.bool? stop, $core.bool? calibrate, - $core.double? pinch, - $core.double? rotate, - $core.double? precisePinch, - $core.double? preciseRotate, + $core.double? moveRotate, + $core.double? moveLift, + $core.double? moveGripper, }) { final _result = create(); + if (stop != null) { + _result.stop = stop; + } if (calibrate != null) { _result.calibrate = calibrate; } - if (pinch != null) { - _result.pinch = pinch; - } - if (rotate != null) { - _result.rotate = rotate; + if (moveRotate != null) { + _result.moveRotate = moveRotate; } - if (precisePinch != null) { - _result.precisePinch = precisePinch; + if (moveLift != null) { + _result.moveLift = moveLift; } - if (preciseRotate != null) { - _result.preciseRotate = preciseRotate; + if (moveGripper != null) { + _result.moveGripper = moveGripper; } return _result; } @@ -566,178 +514,48 @@ class GripperCommand extends $pb.GeneratedMessage { static GripperCommand? _defaultInstance; @$pb.TagNumber(1) - $core.bool get calibrate => $_getBF(0); + $core.bool get stop => $_getBF(0); @$pb.TagNumber(1) - set calibrate($core.bool v) { $_setBool(0, v); } + set stop($core.bool v) { $_setBool(0, v); } @$pb.TagNumber(1) - $core.bool hasCalibrate() => $_has(0); + $core.bool hasStop() => $_has(0); @$pb.TagNumber(1) - void clearCalibrate() => clearField(1); + void clearStop() => clearField(1); @$pb.TagNumber(2) - $core.double get pinch => $_getN(1); + $core.bool get calibrate => $_getBF(1); @$pb.TagNumber(2) - set pinch($core.double v) { $_setFloat(1, v); } + set calibrate($core.bool v) { $_setBool(1, v); } @$pb.TagNumber(2) - $core.bool hasPinch() => $_has(1); + $core.bool hasCalibrate() => $_has(1); @$pb.TagNumber(2) - void clearPinch() => clearField(2); + void clearCalibrate() => clearField(2); @$pb.TagNumber(3) - $core.double get rotate => $_getN(2); + $core.double get moveRotate => $_getN(2); @$pb.TagNumber(3) - set rotate($core.double v) { $_setFloat(2, v); } + set moveRotate($core.double v) { $_setFloat(2, v); } @$pb.TagNumber(3) - $core.bool hasRotate() => $_has(2); + $core.bool hasMoveRotate() => $_has(2); @$pb.TagNumber(3) - void clearRotate() => clearField(3); + void clearMoveRotate() => clearField(3); @$pb.TagNumber(4) - $core.double get precisePinch => $_getN(3); + $core.double get moveLift => $_getN(3); @$pb.TagNumber(4) - set precisePinch($core.double v) { $_setFloat(3, v); } + set moveLift($core.double v) { $_setFloat(3, v); } @$pb.TagNumber(4) - $core.bool hasPrecisePinch() => $_has(3); + $core.bool hasMoveLift() => $_has(3); @$pb.TagNumber(4) - void clearPrecisePinch() => clearField(4); + void clearMoveLift() => clearField(4); @$pb.TagNumber(5) - $core.double get preciseRotate => $_getN(4); + $core.double get moveGripper => $_getN(4); @$pb.TagNumber(5) - set preciseRotate($core.double v) { $_setFloat(4, v); } + set moveGripper($core.double v) { $_setFloat(4, v); } @$pb.TagNumber(5) - $core.bool hasPreciseRotate() => $_has(4); + $core.bool hasMoveGripper() => $_has(4); @$pb.TagNumber(5) - void clearPreciseRotate() => clearField(5); -} - -class HreiData extends $pb.GeneratedMessage { - static final $pb.BuilderInfo _i = $pb.BuilderInfo(const $core.bool.fromEnvironment('protobuf.omit_message_names') ? '' : 'HreiData', createEmptyInstance: create) - ..aOM(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'armData', subBuilder: ArmData.create) - ..aOM(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'gripperData', subBuilder: GripperData.create) - ..hasRequiredFields = false - ; - - HreiData._() : super(); - factory HreiData({ - ArmData? armData, - GripperData? gripperData, - }) { - final _result = create(); - if (armData != null) { - _result.armData = armData; - } - if (gripperData != null) { - _result.gripperData = gripperData; - } - return _result; - } - factory HreiData.fromBuffer($core.List<$core.int> i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromBuffer(i, r); - factory HreiData.fromJson($core.String i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromJson(i, r); - @$core.Deprecated( - 'Using this can add significant overhead to your binary. ' - 'Use [GeneratedMessageGenericExtensions.deepCopy] instead. ' - 'Will be removed in next major version') - HreiData clone() => HreiData()..mergeFromMessage(this); - @$core.Deprecated( - 'Using this can add significant overhead to your binary. ' - 'Use [GeneratedMessageGenericExtensions.rebuild] instead. ' - 'Will be removed in next major version') - HreiData copyWith(void Function(HreiData) updates) => super.copyWith((message) => updates(message as HreiData)) as HreiData; // ignore: deprecated_member_use - $pb.BuilderInfo get info_ => _i; - @$core.pragma('dart2js:noInline') - static HreiData create() => HreiData._(); - HreiData createEmptyInstance() => create(); - static $pb.PbList createRepeated() => $pb.PbList(); - @$core.pragma('dart2js:noInline') - static HreiData getDefault() => _defaultInstance ??= $pb.GeneratedMessage.$_defaultFor(create); - static HreiData? _defaultInstance; - - @$pb.TagNumber(1) - ArmData get armData => $_getN(0); - @$pb.TagNumber(1) - set armData(ArmData v) { setField(1, v); } - @$pb.TagNumber(1) - $core.bool hasArmData() => $_has(0); - @$pb.TagNumber(1) - void clearArmData() => clearField(1); - @$pb.TagNumber(1) - ArmData ensureArmData() => $_ensure(0); - - @$pb.TagNumber(2) - GripperData get gripperData => $_getN(1); - @$pb.TagNumber(2) - set gripperData(GripperData v) { setField(2, v); } - @$pb.TagNumber(2) - $core.bool hasGripperData() => $_has(1); - @$pb.TagNumber(2) - void clearGripperData() => clearField(2); - @$pb.TagNumber(2) - GripperData ensureGripperData() => $_ensure(1); -} - -class HreiCommand extends $pb.GeneratedMessage { - static final $pb.BuilderInfo _i = $pb.BuilderInfo(const $core.bool.fromEnvironment('protobuf.omit_message_names') ? '' : 'HreiCommand', createEmptyInstance: create) - ..aOM(1, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'armCommand', subBuilder: ArmCommand.create) - ..aOM(2, const $core.bool.fromEnvironment('protobuf.omit_field_names') ? '' : 'gripperCommand', subBuilder: GripperCommand.create) - ..hasRequiredFields = false - ; - - HreiCommand._() : super(); - factory HreiCommand({ - ArmCommand? armCommand, - GripperCommand? gripperCommand, - }) { - final _result = create(); - if (armCommand != null) { - _result.armCommand = armCommand; - } - if (gripperCommand != null) { - _result.gripperCommand = gripperCommand; - } - return _result; - } - factory HreiCommand.fromBuffer($core.List<$core.int> i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromBuffer(i, r); - factory HreiCommand.fromJson($core.String i, [$pb.ExtensionRegistry r = $pb.ExtensionRegistry.EMPTY]) => create()..mergeFromJson(i, r); - @$core.Deprecated( - 'Using this can add significant overhead to your binary. ' - 'Use [GeneratedMessageGenericExtensions.deepCopy] instead. ' - 'Will be removed in next major version') - HreiCommand clone() => HreiCommand()..mergeFromMessage(this); - @$core.Deprecated( - 'Using this can add significant overhead to your binary. ' - 'Use [GeneratedMessageGenericExtensions.rebuild] instead. ' - 'Will be removed in next major version') - HreiCommand copyWith(void Function(HreiCommand) updates) => super.copyWith((message) => updates(message as HreiCommand)) as HreiCommand; // ignore: deprecated_member_use - $pb.BuilderInfo get info_ => _i; - @$core.pragma('dart2js:noInline') - static HreiCommand create() => HreiCommand._(); - HreiCommand createEmptyInstance() => create(); - static $pb.PbList createRepeated() => $pb.PbList(); - @$core.pragma('dart2js:noInline') - static HreiCommand getDefault() => _defaultInstance ??= $pb.GeneratedMessage.$_defaultFor(create); - static HreiCommand? _defaultInstance; - - @$pb.TagNumber(1) - ArmCommand get armCommand => $_getN(0); - @$pb.TagNumber(1) - set armCommand(ArmCommand v) { setField(1, v); } - @$pb.TagNumber(1) - $core.bool hasArmCommand() => $_has(0); - @$pb.TagNumber(1) - void clearArmCommand() => clearField(1); - @$pb.TagNumber(1) - ArmCommand ensureArmCommand() => $_ensure(0); - - @$pb.TagNumber(2) - GripperCommand get gripperCommand => $_getN(1); - @$pb.TagNumber(2) - set gripperCommand(GripperCommand v) { setField(2, v); } - @$pb.TagNumber(2) - $core.bool hasGripperCommand() => $_has(1); - @$pb.TagNumber(2) - void clearGripperCommand() => clearField(2); - @$pb.TagNumber(2) - GripperCommand ensureGripperCommand() => $_ensure(1); + void clearMoveGripper() => clearField(5); } diff --git a/lib/src/data/generated/arm.pbjson.dart b/lib/src/data/generated/arm.pbjson.dart index b5c10263a..84e51da7e 100644 --- a/lib/src/data/generated/arm.pbjson.dart +++ b/lib/src/data/generated/arm.pbjson.dart @@ -20,23 +20,6 @@ const Position$json = const { /// Descriptor for `Position`. Decode as a `google.protobuf.DescriptorProto`. final $typed_data.Uint8List positionDescriptor = $convert.base64Decode('CghQb3NpdGlvbhIMCgF4GAEgASgFUgF4EgwKAXkYAiABKAVSAXkSDAoBehgDIAEoBVIBeg=='); -@$core.Deprecated('Use armCommandDescriptor instead') -const ArmCommand$json = const { - '1': 'ArmCommand', - '2': const [ - const {'1': 'move_to', '3': 1, '4': 1, '5': 11, '6': '.Position', '10': 'moveTo'}, - const {'1': 'calibrate', '3': 2, '4': 1, '5': 8, '10': 'calibrate'}, - const {'1': 'swivel', '3': 3, '4': 1, '5': 2, '10': 'swivel'}, - const {'1': 'extend', '3': 4, '4': 1, '5': 2, '10': 'extend'}, - const {'1': 'lift', '3': 5, '4': 1, '5': 2, '10': 'lift'}, - const {'1': 'precise_swivel', '3': 6, '4': 1, '5': 2, '10': 'preciseSwivel'}, - const {'1': 'precise_lift', '3': 7, '4': 1, '5': 2, '10': 'preciseLift'}, - const {'1': 'precise_extend', '3': 8, '4': 1, '5': 2, '10': 'preciseExtend'}, - ], -}; - -/// Descriptor for `ArmCommand`. Decode as a `google.protobuf.DescriptorProto`. -final $typed_data.Uint8List armCommandDescriptor = $convert.base64Decode('CgpBcm1Db21tYW5kEiIKB21vdmVfdG8YASABKAsyCS5Qb3NpdGlvblIGbW92ZVRvEhwKCWNhbGlicmF0ZRgCIAEoCFIJY2FsaWJyYXRlEhYKBnN3aXZlbBgDIAEoAlIGc3dpdmVsEhYKBmV4dGVuZBgEIAEoAlIGZXh0ZW5kEhIKBGxpZnQYBSABKAJSBGxpZnQSJQoOcHJlY2lzZV9zd2l2ZWwYBiABKAJSDXByZWNpc2VTd2l2ZWwSIQoMcHJlY2lzZV9saWZ0GAcgASgCUgtwcmVjaXNlTGlmdBIlCg5wcmVjaXNlX2V4dGVuZBgIIAEoAlINcHJlY2lzZUV4dGVuZA=='); @$core.Deprecated('Use motorStatusDescriptor instead') const MotorStatus$json = const { '1': 'MotorStatus', @@ -63,52 +46,43 @@ const ArmData$json = const { /// Descriptor for `ArmData`. Decode as a `google.protobuf.DescriptorProto`. final $typed_data.Uint8List armDataDescriptor = $convert.base64Decode('CgdBcm1EYXRhEjMKD2N1cnJlbnRQb3NpdGlvbhgBIAEoCzIJLlBvc2l0aW9uUg9jdXJyZW50UG9zaXRpb24SMQoOdGFyZ2V0UG9zaXRpb24YAiABKAsyCS5Qb3NpdGlvblIOdGFyZ2V0UG9zaXRpb24SIAoEYmFzZRgDIAEoCzIMLk1vdG9yU3RhdHVzUgRiYXNlEigKCHNob3VsZGVyGAQgASgLMgwuTW90b3JTdGF0dXNSCHNob3VsZGVyEiIKBWVsYm93GAUgASgLMgwuTW90b3JTdGF0dXNSBWVsYm93'); +@$core.Deprecated('Use armCommandDescriptor instead') +const ArmCommand$json = const { + '1': 'ArmCommand', + '2': const [ + const {'1': 'stop', '3': 1, '4': 1, '5': 8, '10': 'stop'}, + const {'1': 'calibrate', '3': 2, '4': 1, '5': 8, '10': 'calibrate'}, + const {'1': 'move_swivel', '3': 3, '4': 1, '5': 2, '10': 'moveSwivel'}, + const {'1': 'move_shoulder', '3': 4, '4': 1, '5': 2, '10': 'moveShoulder'}, + const {'1': 'move_elbow', '3': 5, '4': 1, '5': 2, '10': 'moveElbow'}, + ], +}; + +/// Descriptor for `ArmCommand`. Decode as a `google.protobuf.DescriptorProto`. +final $typed_data.Uint8List armCommandDescriptor = $convert.base64Decode('CgpBcm1Db21tYW5kEhIKBHN0b3AYASABKAhSBHN0b3ASHAoJY2FsaWJyYXRlGAIgASgIUgljYWxpYnJhdGUSHwoLbW92ZV9zd2l2ZWwYAyABKAJSCm1vdmVTd2l2ZWwSIwoNbW92ZV9zaG91bGRlchgEIAEoAlIMbW92ZVNob3VsZGVyEh0KCm1vdmVfZWxib3cYBSABKAJSCW1vdmVFbGJvdw=='); @$core.Deprecated('Use gripperDataDescriptor instead') const GripperData$json = const { '1': 'GripperData', '2': const [ - const {'1': 'rotation', '3': 1, '4': 1, '5': 2, '10': 'rotation'}, - const {'1': 'swivel', '3': 2, '4': 1, '5': 2, '10': 'swivel'}, - const {'1': 'pinch', '3': 3, '4': 1, '5': 2, '10': 'pinch'}, - const {'1': 'motor_temperature', '3': 4, '4': 1, '5': 2, '10': 'motorTemperature'}, + const {'1': 'rotate', '3': 1, '4': 1, '5': 11, '6': '.MotorStatus', '10': 'rotate'}, + const {'1': 'lift', '3': 2, '4': 1, '5': 11, '6': '.MotorStatus', '10': 'lift'}, + const {'1': 'pinch', '3': 3, '4': 1, '5': 11, '6': '.MotorStatus', '10': 'pinch'}, ], }; /// Descriptor for `GripperData`. Decode as a `google.protobuf.DescriptorProto`. -final $typed_data.Uint8List gripperDataDescriptor = $convert.base64Decode('CgtHcmlwcGVyRGF0YRIaCghyb3RhdGlvbhgBIAEoAlIIcm90YXRpb24SFgoGc3dpdmVsGAIgASgCUgZzd2l2ZWwSFAoFcGluY2gYAyABKAJSBXBpbmNoEisKEW1vdG9yX3RlbXBlcmF0dXJlGAQgASgCUhBtb3RvclRlbXBlcmF0dXJl'); +final $typed_data.Uint8List gripperDataDescriptor = $convert.base64Decode('CgtHcmlwcGVyRGF0YRIkCgZyb3RhdGUYASABKAsyDC5Nb3RvclN0YXR1c1IGcm90YXRlEiAKBGxpZnQYAiABKAsyDC5Nb3RvclN0YXR1c1IEbGlmdBIiCgVwaW5jaBgDIAEoCzIMLk1vdG9yU3RhdHVzUgVwaW5jaA=='); @$core.Deprecated('Use gripperCommandDescriptor instead') const GripperCommand$json = const { '1': 'GripperCommand', '2': const [ - const {'1': 'calibrate', '3': 1, '4': 1, '5': 8, '10': 'calibrate'}, - const {'1': 'pinch', '3': 2, '4': 1, '5': 2, '10': 'pinch'}, - const {'1': 'rotate', '3': 3, '4': 1, '5': 2, '10': 'rotate'}, - const {'1': 'precise_pinch', '3': 4, '4': 1, '5': 2, '10': 'precisePinch'}, - const {'1': 'precise_rotate', '3': 5, '4': 1, '5': 2, '10': 'preciseRotate'}, + const {'1': 'stop', '3': 1, '4': 1, '5': 8, '10': 'stop'}, + const {'1': 'calibrate', '3': 2, '4': 1, '5': 8, '10': 'calibrate'}, + const {'1': 'move_rotate', '3': 3, '4': 1, '5': 2, '10': 'moveRotate'}, + const {'1': 'move_lift', '3': 4, '4': 1, '5': 2, '10': 'moveLift'}, + const {'1': 'move_gripper', '3': 5, '4': 1, '5': 2, '10': 'moveGripper'}, ], }; /// Descriptor for `GripperCommand`. Decode as a `google.protobuf.DescriptorProto`. -final $typed_data.Uint8List gripperCommandDescriptor = $convert.base64Decode('Cg5HcmlwcGVyQ29tbWFuZBIcCgljYWxpYnJhdGUYASABKAhSCWNhbGlicmF0ZRIUCgVwaW5jaBgCIAEoAlIFcGluY2gSFgoGcm90YXRlGAMgASgCUgZyb3RhdGUSIwoNcHJlY2lzZV9waW5jaBgEIAEoAlIMcHJlY2lzZVBpbmNoEiUKDnByZWNpc2Vfcm90YXRlGAUgASgCUg1wcmVjaXNlUm90YXRl'); -@$core.Deprecated('Use hreiDataDescriptor instead') -const HreiData$json = const { - '1': 'HreiData', - '2': const [ - const {'1': 'arm_data', '3': 1, '4': 1, '5': 11, '6': '.ArmData', '10': 'armData'}, - const {'1': 'gripper_data', '3': 2, '4': 1, '5': 11, '6': '.GripperData', '10': 'gripperData'}, - ], -}; - -/// Descriptor for `HreiData`. Decode as a `google.protobuf.DescriptorProto`. -final $typed_data.Uint8List hreiDataDescriptor = $convert.base64Decode('CghIcmVpRGF0YRIjCghhcm1fZGF0YRgBIAEoCzIILkFybURhdGFSB2FybURhdGESLwoMZ3JpcHBlcl9kYXRhGAIgASgLMgwuR3JpcHBlckRhdGFSC2dyaXBwZXJEYXRh'); -@$core.Deprecated('Use hreiCommandDescriptor instead') -const HreiCommand$json = const { - '1': 'HreiCommand', - '2': const [ - const {'1': 'arm_command', '3': 1, '4': 1, '5': 11, '6': '.ArmCommand', '10': 'armCommand'}, - const {'1': 'gripper_command', '3': 2, '4': 1, '5': 11, '6': '.GripperCommand', '10': 'gripperCommand'}, - ], -}; - -/// Descriptor for `HreiCommand`. Decode as a `google.protobuf.DescriptorProto`. -final $typed_data.Uint8List hreiCommandDescriptor = $convert.base64Decode('CgtIcmVpQ29tbWFuZBIsCgthcm1fY29tbWFuZBgBIAEoCzILLkFybUNvbW1hbmRSCmFybUNvbW1hbmQSOAoPZ3JpcHBlcl9jb21tYW5kGAIgASgLMg8uR3JpcHBlckNvbW1hbmRSDmdyaXBwZXJDb21tYW5k'); +final $typed_data.Uint8List gripperCommandDescriptor = $convert.base64Decode('Cg5HcmlwcGVyQ29tbWFuZBISCgRzdG9wGAEgASgIUgRzdG9wEhwKCWNhbGlicmF0ZRgCIAEoCFIJY2FsaWJyYXRlEh8KC21vdmVfcm90YXRlGAMgASgCUgptb3ZlUm90YXRlEhsKCW1vdmVfbGlmdBgEIAEoAlIIbW92ZUxpZnQSIQoMbW92ZV9ncmlwcGVyGAUgASgCUgttb3ZlR3JpcHBlcg=='); diff --git a/lib/src/models/data/home.dart b/lib/src/models/data/home.dart index 14c0ecae6..39dc29577 100644 --- a/lib/src/models/data/home.dart +++ b/lib/src/models/data/home.dart @@ -28,14 +28,6 @@ class HomeModel extends Model { _messageTimer = Timer(const Duration(seconds: 5), () { message = null; notifyListeners(); }); } - /// The list of controls for this mode. - List get controls => [ // TODO: replace with actual backend - "Start dig sequence: START", - "Change operation mode: BACK", - "Move Auger: D-pad Up/Down", - "...", - ]; - /// Changes the mode based on an index. void changeMode(int index) { mode = OperatingMode.values[index]; @@ -43,4 +35,11 @@ class HomeModel extends Model { services.gamepad.vibrate(); notifyListeners(); } + + /// Switches to the next mode. + void nextMode() { + int index = mode.index + 1; + if (index == OperatingMode.values.length) index = 0; + changeMode(index); + } } diff --git a/lib/src/models/data/video.dart b/lib/src/models/data/video.dart index 357311952..2b94d0078 100644 --- a/lib/src/models/data/video.dart +++ b/lib/src/models/data/video.dart @@ -42,7 +42,7 @@ class VideoModel extends Model { handler: updateFrame, ); frameUpdater = Timer.periodic( - const Duration(milliseconds: 17), // 60 FPS + const Duration(milliseconds: 42), // 24 FPS (_) => notifyListeners() ); // TODO: Read the layout from Settings diff --git a/lib/src/models/rover/arm.dart b/lib/src/models/rover/arm.dart new file mode 100644 index 000000000..b75427ef4 --- /dev/null +++ b/lib/src/models/rover/arm.dart @@ -0,0 +1,41 @@ +import "controller.dart"; + +/// Controls the arm. +class ArmController extends Controller { + @override + List parseInputs(GamepadState state) => [ + // ARM + if (state.leftShoulder) ArmCommand(moveSwivel: -0.25), + if (state.rightShoulder) ArmCommand(moveSwivel: 0.25), + if (state.normalRightY != 0) ArmCommand(moveElbow: state.normalRightY), + if (state.normalLeftY != 0) ArmCommand(moveShoulder: -state.normalLeftY), + + // GRIPPER + if (state.leftTrigger > 0) GripperCommand(moveGripper: -state.normalLeftTrigger), + if (state.rightTrigger > 0) GripperCommand(moveGripper: state.normalRightTrigger), + if (state.dpadUp) GripperCommand(moveLift: 1), + if (state.dpadDown) GripperCommand(moveLift: -1), + if (state.normalRightX != 0) GripperCommand(moveRotate: 1.25*state.normalRightX), + + if (state.buttonBack) ArmCommand(stop: true), + if (state.buttonBack) GripperCommand(stop: true), + // if (state.buttonStart) ArmCommand(calibrate: true), + // if (state.buttonStart) GripperCommand(calibrate: true), + ]; + + @override + List get onDispose => [ + ArmCommand(stop: true), + GripperCommand(stop: true), + ]; + + @override + Map get controls => { + "Swivel": "Bumpers", + "Shoulder": "Left joystick (vertical)", + "Elbow": "Right joystick (vertical)", + "Gripper Lift": "D-pad up/down", + "Gripper rotate": "Right joystick (horizontal)", + "Pinch": "Triggers", + }; +} diff --git a/lib/src/models/rover/controller.dart b/lib/src/models/rover/controller.dart index 6b3fa2f9a..0af26e81c 100644 --- a/lib/src/models/rover/controller.dart +++ b/lib/src/models/rover/controller.dart @@ -5,6 +5,7 @@ import "package:rover_dashboard/models.dart"; import "package:rover_dashboard/services.dart"; import "../model.dart"; +import "arm.dart"; import "drive.dart"; import "stub.dart"; @@ -26,13 +27,18 @@ abstract class Controller extends Model { /// Reads the gamepad and controls the rover when triggered. late final Timer gamepadTimer; + /// Whether the start button has been pressed. + /// + /// When the start button is released, the dashboard will switch to the next mode. + bool isStartPressed = false; + /// Allows this class to be subclassed. Controller(); /// Constructs the appropriate [Controller] for each mode. factory Controller.forMode(OperatingMode mode) { switch (mode) { - case OperatingMode.arm: return StubController(); + case OperatingMode.arm: return ArmController(); case OperatingMode.science: return StubController(); case OperatingMode.autonomy: return StubController(); case OperatingMode.drive: return DriveController(); @@ -62,6 +68,9 @@ abstract class Controller extends Model { /// Use this to stop the rover when the user switches modes. Iterable get onDispose; + /// A human-readable list of controls. + Map get controls; + /// Sends a command over the network or over Serial. Future sendMessage(Message message) async { if (models.serial.isConnected) { @@ -72,8 +81,13 @@ abstract class Controller extends Model { } /// Reads the gamepad, chooses commands, and sends them to the rover. - void _update([_]) { + Future _update([_]) async { services.gamepad.update(); + if (services.gamepad.state.buttonStart) { + isStartPressed = true; + } else if (isStartPressed) { + models.home.nextMode(); + } final messages = parseInputs(services.gamepad.state); messages.forEach(sendMessage); } diff --git a/lib/src/models/rover/core.dart b/lib/src/models/rover/core.dart index 7ab746f63..a3770325d 100644 --- a/lib/src/models/rover/core.dart +++ b/lib/src/models/rover/core.dart @@ -9,10 +9,10 @@ import "../model.dart"; const connectionIncrement = 0.2; /// How long to wait between handshakes. -const handshakeInterval = Duration(seconds: 1); +const handshakeInterval = Duration(milliseconds: 200); /// How long to wait for incoming handshakes after sending them out. -const handshakeWaitDelay = Duration(milliseconds: 200); +const handshakeWaitDelay = Duration(milliseconds: 50); /// Monitors the connection to the rover. class RoverCore extends Model { diff --git a/lib/src/models/rover/drive.dart b/lib/src/models/rover/drive.dart index 2eaf1dc70..9fd49c0bb 100644 --- a/lib/src/models/rover/drive.dart +++ b/lib/src/models/rover/drive.dart @@ -10,10 +10,27 @@ class DriveController extends Controller { @override List parseInputs(GamepadState state) => [ - DriveCommand(setLeft: true, left: state.leftThumbstickY.normalizeJoystick.clamp(-1, 1)), + // Manual controls + DriveCommand(setLeft: true, left: -1*state.leftThumbstickY.normalizeJoystick.clamp(-1, 1)), DriveCommand(setRight: true, right: state.rightThumbstickY.normalizeJoystick.clamp(-1, 1)), if (state.dpadUp) updateThrottle(throttleIncrement), if (state.dpadDown) updateThrottle(-throttleIncrement), + + // More intuitive controls + if (state.leftShoulder) ...[ + DriveCommand(setLeft: true, left: 1), + DriveCommand(setRight: true, right: 1), + ] else if (state.rightShoulder)...[ + DriveCommand(setLeft: true, left: -1), + DriveCommand(setRight: true, right: -1), + ], + if (state.leftTrigger > 0) ...[ + DriveCommand(setLeft: true, left: state.normalLeftTrigger), + DriveCommand(setRight: true, right: -1*state.normalRightTrigger), + ] else if (state.rightTrigger > 0)...[ + DriveCommand(setLeft: true, left: -1*state.normalLeftTrigger), + DriveCommand(setRight: true, right: state.normalRightTrigger), + ] ]; /// Updates the throttle by [throttleIncrement], clamping at [0, 1]. @@ -29,4 +46,13 @@ class DriveController extends Controller { DriveCommand(setLeft: true, left: 0), DriveCommand(setLeft: false, left: 0), ]; + + @override + Map get controls => { + "Left Throttle": "Left joystick (vertical)", + "Right Throttle": "Right joystick (vertical)", + "Drive Straight": "Triggers", + "Turn in place": "Bumpers", + "Adjust speed": "D-pad up/down", + }; } diff --git a/lib/src/models/rover/stub.dart b/lib/src/models/rover/stub.dart index 5f2f830c2..baffb1a48 100644 --- a/lib/src/models/rover/stub.dart +++ b/lib/src/models/rover/stub.dart @@ -7,4 +7,7 @@ class StubController extends Controller { @override List get onDispose => []; + + @override + Map get controls => {}; } diff --git a/lib/src/pages/home.dart b/lib/src/pages/home.dart index 8b265554a..76b3b10ad 100644 --- a/lib/src/pages/home.dart +++ b/lib/src/pages/home.dart @@ -31,52 +31,81 @@ class OperatingModePage { /// The main dashboard page. /// /// TODO: Define what exactly will go here. -class HomePage extends StatelessWidget { +class HomePage extends StatefulWidget { @override - Widget build(BuildContext context) => DefaultTabController( - length: OperatingModePage.allPages.length, - child: Scaffold( - appBar: AppBar( - title: const Text("Dashboard"), - bottom: PreferredSize( - preferredSize: const Size.fromHeight(32), - child: TabBar( - onTap: models.home.changeMode, - tabs: [ - for (final page in OperatingModePage.allPages) Row( - mainAxisAlignment: MainAxisAlignment.center, - children: [ - Text(page.mode.name), - const SizedBox(width: 8), - Icon(page.icon) - ] - ) - ], - ) - ), - actions: [ - IconButton( - icon: const Icon(Icons.settings), - onPressed: () => Navigator.of(context).pushNamed(Routes.settings), - ), - ] - ), - body: Column( - children: [ - Expanded(child: Row( - children: [ - Expanded(child: TabBarView( - physics: const NeverScrollableScrollPhysics(), // must use buttons - children: [ - for (final page in OperatingModePage.allPages) page.page - ] - )), - Sidebar(), - ] - )), - Footer(), - ] + HomeState createState() => HomeState(); +} + +/// A state for the home page. +/// +/// Responsible for listening to changes in [HomeModel.mode] and animating the UI. +class HomeState extends State with SingleTickerProviderStateMixin { + /// Controls tab-related UI, like animation. + late final TabController controller; + + @override + void initState() { + super.initState(); + models.home.addListener(listener); + controller = TabController(length: OperatingMode.values.length, vsync: this); + } + + @override + void dispose() { + controller.dispose(); + models.home.removeListener(listener); + super.dispose(); + } + + /// Listens to mode changes and animates [controller]. + void listener() { + controller.animateTo(models.home.mode.index); + } + + @override + Widget build(BuildContext context) => Scaffold( + appBar: AppBar( + title: const Text("Dashboard"), + bottom: PreferredSize( + preferredSize: const Size.fromHeight(32), + child: TabBar( + controller: controller, + onTap: models.home.changeMode, + tabs: [ + for (final page in OperatingModePage.allPages) Row( + mainAxisAlignment: MainAxisAlignment.center, + children: [ + Text(page.mode.name), + const SizedBox(width: 8), + Icon(page.icon) + ] + ) + ], + ) ), - ) + actions: [ + IconButton( + icon: const Icon(Icons.settings), + onPressed: () => Navigator.of(context).pushNamed(Routes.settings), + ), + ] + ), + body: Column( + children: [ + Expanded(child: Row( + children: [ + Expanded(child: TabBarView( + controller: controller, + physics: const NeverScrollableScrollPhysics(), // must use buttons + children: [ + for (final page in OperatingModePage.allPages) page.page + ] + )), + Sidebar(), + ] + )), + Footer(), + ] + ), ); } diff --git a/lib/src/services/gamepad.dart b/lib/src/services/gamepad.dart index 6e331a44d..9c7dff2be 100644 --- a/lib/src/services/gamepad.dart +++ b/lib/src/services/gamepad.dart @@ -9,11 +9,38 @@ const epsilon = 0.01; /// An extension to do gamepad math. extension GamepadNumbers on num { - /// Normalizes joystick inputs to be between 0 and 1. + /// Normalizes joystick inputs to be between -1 and 1. double get normalizeJoystick { final value = (this - 128) / 32768; - return (value.abs() < epsilon) ? 0 : value; + return (value.abs() < epsilon) ? 0 : value.clamp(-1, 1); } + + /// Normalizes the trigger inputs to be between 0 and 1. + double get normalizeTrigger { + final value = this / 256; + return (value.abs() < epsilon) ? 0 : value.clamp(0, 1); + } +} + +/// More user-friendly values from [GamepadState]. +extension GamepadUtils on GamepadState { + /// Returns a normalized value for the left trigger. See [GamepadNumbers.normalizeTrigger]. + double get normalLeftTrigger => leftTrigger.normalizeTrigger; + + /// Returns a normalized value for the right trigger. See [GamepadNumbers.normalizeTrigger]. + double get normalRightTrigger => rightTrigger.normalizeTrigger; + + /// Returns a normalized value for the left joystick's X-axis. See [GamepadNumbers.normalizeJoystick]. + double get normalLeftX => leftThumbstickX.normalizeJoystick; + + /// Returns a normalized value for the left joystick's Y-axis. See [GamepadNumbers.normalizeJoystick]. + double get normalLeftY => leftThumbstickY.normalizeJoystick; + + /// Returns a normalized value for the right joystick's X-axis. See [GamepadNumbers.normalizeJoystick]. + double get normalRightX => rightThumbstickX.normalizeJoystick; + + /// Returns a normalized value for the right joystick's Y-axis. See [GamepadNumbers.normalizeJoystick]. + double get normalRightY => rightThumbstickY.normalizeJoystick; } /// The maximum amount of gamepads a user can have. diff --git a/lib/src/widgets/atomic/video_feed.dart b/lib/src/widgets/atomic/video_feed.dart index f30863429..e0ee76b51 100644 --- a/lib/src/widgets/atomic/video_feed.dart +++ b/lib/src/widgets/atomic/video_feed.dart @@ -1,3 +1,5 @@ +import "dart:async"; +import "dart:math" as math; import "dart:typed_data"; import "dart:ui" as ui; import "package:flutter/material.dart"; @@ -5,6 +7,41 @@ import "package:flutter/material.dart"; import "package:rover_dashboard/data.dart"; import "package:rover_dashboard/models.dart"; +/// A helper class to load and manage resources used by a [ui.Image]. +/// +/// To use: +/// - Call [load] with your image data +/// - Pass [image] to a [RawImage] widget, if it isn't null +/// - Call [dispose] to release all resources used by the image. +/// +/// It is safe to call [load] or [dispose] multiple times, and calling [load] +/// will automatically call [dispose] on the existing resources. +class ImageLoader { + /// The `dart:ui` instance of the current frame. + ui.Image? image; + + /// The codec used by [image]. + ui.Codec? codec; + + /// Whether this loader has been initialized. + bool get hasImage => image != null; + + /// Processes the next frame and stores the result in [image]. + Future load(List bytes) async { + // if (hasImage) dispose(); + final ulist = Uint8List.fromList(bytes.toList()); + codec = await ui.instantiateImageCodec(ulist); + final frame = await codec!.getNextFrame(); + image = frame.image; + } + + /// Disposes all the resources associated with the current frame. + void dispose() { + codec?.dispose(); + image?.dispose(); + } +} + /// Displays frames of a [CameraFeed]. class VideoFeed extends StatefulWidget { /// The feed to show in this widget. @@ -30,12 +67,12 @@ class VideoFeedState extends State { /// The feed being streamed. late CameraFeed feed; - /// The `dart:ui` instance of the current frame. - ui.Image? image; - /// Whether [feed] has a frame to show. bool get hasFrame => feed.frame != null; + /// A helper class responsible for managing and loading an image. + final imageLoader = ImageLoader(); + @override void initState() { super.initState(); @@ -46,29 +83,15 @@ class VideoFeedState extends State { @override void dispose() { models.video.removeListener(updateImage); - image?.dispose(); + imageLoader.dispose(); super.dispose(); } - /// Decodes and renders the next frame. - /// - /// This process happens off-screen. To display the resulting image, use a [RawImage] widget. - Future loadImage(List bytes) async { - final ulist = Uint8List.fromList(bytes); - final buffer = await ui.ImmutableBuffer.fromUint8List(ulist); - final descriptor = await ui.ImageDescriptor.encoded(buffer); - final codec = await descriptor.instantiateCodec(); - final frame = await codec.getNextFrame(); - return frame.image; - } - /// Grabs the new frame, renders it, and replaces the old frame. Future updateImage() async { if (!hasFrame) return; - final newImage = await loadImage(feed.frame!); - if (!mounted) return; - image?.dispose(); - setState(() => image = newImage); + await imageLoader.load(feed.frame!); + if (mounted) setState(() { }); } @override @@ -80,8 +103,14 @@ class VideoFeedState extends State { width: double.infinity, margin: const EdgeInsets.all(1), alignment: Alignment.center, - child: image == null ? Text(errorMessage) - : Row(children: [Expanded(child: RawImage(image: image, fit: BoxFit.fill))]), + child: !imageLoader.hasImage ? Text(errorMessage) + : Row(children: [ + // Special case: ARM_BASE camera is flipped, let's unflip it in software + Expanded(child: feed.id == CameraName.ARM_BASE + ? Transform.rotate(angle: math.pi, child: RawImage(image: imageLoader.image, fit: BoxFit.fill)) + : RawImage(image: imageLoader.image, fit: BoxFit.fill) + ) + ]), ), Row( mainAxisAlignment: MainAxisAlignment.end, @@ -119,11 +148,8 @@ class VideoFeedState extends State { Future selectNewFeed(CameraFeed newFeed) async { await models.video.disableFeed(feed); await models.video.enableFeed(newFeed); - image?.dispose(); - setState(() { - feed = newFeed; - image = null; - }); + imageLoader.dispose(); + setState(() => feed = newFeed); await updateImage(); } } diff --git a/lib/src/widgets/generic/metrics_list.dart b/lib/src/widgets/generic/metrics_list.dart index 9d28ddbc2..d5a404ded 100644 --- a/lib/src/widgets/generic/metrics_list.dart +++ b/lib/src/widgets/generic/metrics_list.dart @@ -10,8 +10,7 @@ class MetricsList extends StatelessWidget { @override Widget build(BuildContext context) => Consumer( - builder: (context, rover, _) => ListView( - shrinkWrap: true, + builder: (context, rover, _) => Column( children: [ Text("Metrics", style: Theme.of(context).textTheme.displaySmall), for (final metrics in rover.metrics.allMetrics) ExpansionTile( diff --git a/lib/src/widgets/navigation/sidebar.dart b/lib/src/widgets/navigation/sidebar.dart index f802275ff..890ca6035 100644 --- a/lib/src/widgets/navigation/sidebar.dart +++ b/lib/src/widgets/navigation/sidebar.dart @@ -11,15 +11,19 @@ class Sidebar extends StatelessWidget { width: 225, alignment: Alignment.center, color: Theme.of(context).colorScheme.surfaceVariant, - child: Consumer( + child: Consumer( child: const MetricsList(), - builder: (context, model, metrics) => ListView( + builder: (context, rover, metrics) => ListView( padding: const EdgeInsets.symmetric(horizontal: 16), children: [ metrics!, + const Divider(), Text("Controls", style: Theme.of(context).textTheme.displaySmall), const SizedBox(height: 16), - for (final control in model.controls) Text(control), + for (final entry in rover.controller.controls.entries) ...[ + Text(entry.key, style: Theme.of(context).textTheme.titleLarge), + Text(" ${entry.value}", style: Theme.of(context).textTheme.titleMedium), + ] ] ) )