diff --git a/Writerside/topics/Robot-Config.md b/Writerside/topics/Robot-Config.md index 9a6e9beb..a6bb9ce7 100644 --- a/Writerside/topics/Robot-Config.md +++ b/Writerside/topics/Robot-Config.md @@ -81,8 +81,7 @@ True Max Drive Speed > > It is very important that the True Max Drive Speed is measured for your actual robot. This value is not simply a "max > velocity" limit on the robot. It encodes information about how much motor torque can actually be used to accelerate -> the -> robot. +> the robot. > > This can be easily measured by driving the robot in a straight line as fast as possible on a charged battery, and > measuring the robot's maximum velocity. @@ -107,4 +106,9 @@ Drive Current Limit ## Module Offsets The locations of each swerve module relative to the center of the robot, in meters. These should be the same offsets -used to create your kinematics in code. Only available for swerve drive robots. \ No newline at end of file +used to create your kinematics in code. Only available for swerve drive robots. + +## Robot Features + +Robot features are shapes that can be added to the robot in the GUI. These can be used to represent intakes, shooting +trajectories, etc. Current features include: rectangle, circle, and lines. diff --git a/lib/commands/command.dart b/lib/commands/command.dart index abb3d736..3ad3c4ad 100644 --- a/lib/commands/command.dart +++ b/lib/commands/command.dart @@ -25,43 +25,30 @@ abstract class Command { static Command? fromJson(Map json) { String? type = json['type']; - - if (type == 'wait') { - return WaitCommand.fromDataJson(json['data'] ?? {}); - } else if (type == 'named') { - return NamedCommand.fromDataJson(json['data'] ?? {}); - } else if (type == 'path') { - return PathCommand.fromDataJson(json['data'] ?? {}); - } else if (type == 'sequential') { - return SequentialCommandGroup.fromDataJson(json['data'] ?? {}); - } else if (type == 'parallel') { - return ParallelCommandGroup.fromDataJson(json['data'] ?? {}); - } else if (type == 'race') { - return RaceCommandGroup.fromDataJson(json['data'] ?? {}); - } else if (type == 'deadline') { - return DeadlineCommandGroup.fromDataJson(json['data'] ?? {}); - } - - return null; + Map data = json['data'] ?? {}; + + return switch (type) { + 'wait' => WaitCommand.fromDataJson(data), + 'named' => NamedCommand.fromDataJson(data), + 'path' => PathCommand.fromDataJson(data), + 'sequential' => SequentialCommandGroup.fromDataJson(data), + 'parallel' => ParallelCommandGroup.fromDataJson(data), + 'race' => RaceCommandGroup.fromDataJson(data), + 'deadline' => DeadlineCommandGroup.fromDataJson(data), + _ => null, + }; } static Command? fromType(String type, {List? commands}) { - if (type == 'named') { - return NamedCommand(); - } else if (type == 'wait') { - return WaitCommand(); - } else if (type == 'path') { - return PathCommand(); - } else if (type == 'sequential') { - return SequentialCommandGroup(commands: commands ?? []); - } else if (type == 'parallel') { - return ParallelCommandGroup(commands: commands ?? []); - } else if (type == 'race') { - return RaceCommandGroup(commands: commands ?? []); - } else if (type == 'deadline') { - return DeadlineCommandGroup(commands: commands ?? []); - } - - return null; + return switch (type) { + 'named' => NamedCommand(), + 'wait' => WaitCommand(), + 'path' => PathCommand(), + 'sequential' => SequentialCommandGroup(commands: commands ?? []), + 'parallel' => ParallelCommandGroup(commands: commands ?? []), + 'race' => RaceCommandGroup(commands: commands ?? []), + 'deadline' => DeadlineCommandGroup(commands: commands ?? []), + _ => null, + }; } } diff --git a/lib/pages/home_page.dart b/lib/pages/home_page.dart index d8c3de4e..5b4ac2b6 100644 --- a/lib/pages/home_page.dart +++ b/lib/pages/home_page.dart @@ -548,6 +548,8 @@ class _HomePageState extends State with TickerProviderStateMixin { json, PrefsKeys.defaultMaxAngVel, Defaults.defaultMaxAngVel); _setPrefDoubleFromJSON( json, PrefsKeys.defaultMaxAngAccel, Defaults.defaultMaxAngAccel); + _setPrefDoubleFromJSON( + json, PrefsKeys.defaultNominalVoltage, Defaults.defaultNominalVoltage); _setPrefDoubleFromJSON(json, PrefsKeys.robotMass, Defaults.robotMass); _setPrefDoubleFromJSON(json, PrefsKeys.robotMOI, Defaults.robotMOI); _setPrefDoubleFromJSON( @@ -574,6 +576,8 @@ class _HomePageState extends State with TickerProviderStateMixin { json, PrefsKeys.bumperOffsetX, Defaults.bumperOffsetX); _setPrefDoubleFromJSON( json, PrefsKeys.bumperOffsetY, Defaults.bumperOffsetY); + widget.prefs.setString(PrefsKeys.robotFeatures, + json[PrefsKeys.robotFeatures] ?? Defaults.robotFeatures); } void _setPrefDoubleFromJSON( @@ -616,6 +620,9 @@ class _HomePageState extends State with TickerProviderStateMixin { PrefsKeys.defaultMaxAngAccel: widget.prefs.getDouble(PrefsKeys.defaultMaxAngAccel) ?? Defaults.defaultMaxAccel, + PrefsKeys.defaultNominalVoltage: + widget.prefs.getDouble(PrefsKeys.defaultNominalVoltage) ?? + Defaults.defaultNominalVoltage, PrefsKeys.robotMass: widget.prefs.getDouble(PrefsKeys.robotMass) ?? Defaults.robotMass, PrefsKeys.robotMOI: @@ -660,6 +667,9 @@ class _HomePageState extends State with TickerProviderStateMixin { PrefsKeys.bumperOffsetY: widget.prefs.getDouble(PrefsKeys.bumperOffsetY) ?? Defaults.bumperOffsetY, + PrefsKeys.robotFeatures: + widget.prefs.getStringList(PrefsKeys.robotFeatures) ?? + Defaults.robotFeatures, }; settingsFile.writeAsString(encoder.convert(settings)).then((_) { diff --git a/lib/pages/telemetry_page.dart b/lib/pages/telemetry_page.dart index a31826d7..3a27639e 100644 --- a/lib/pages/telemetry_page.dart +++ b/lib/pages/telemetry_page.dart @@ -1,10 +1,12 @@ import 'dart:collection'; +import 'dart:convert'; import 'dart:math'; import 'package:fl_chart/fl_chart.dart'; import 'package:flutter/foundation.dart'; import 'package:flutter/material.dart'; import 'package:flutter_animate/flutter_animate.dart'; +import 'package:pathplanner/robot_features/feature.dart'; import 'package:pathplanner/services/pplib_telemetry.dart'; import 'package:pathplanner/util/path_painter_util.dart'; import 'package:pathplanner/util/prefs.dart'; @@ -39,6 +41,7 @@ class _TelemetryPageState extends State { late final Size _robotSize; late final Translation2d _bumperOffset; late bool _useSim; + final List _robotFeatures = []; bool _gotCurrentPose = false; bool _gotTargetPose = false; @@ -62,6 +65,16 @@ class _TelemetryPageState extends State { _useSim = widget.prefs.getBool(PrefsKeys.telemetryUseSim) ?? Defaults.telemetryUseSim; + for (String featureJson + in widget.prefs.getStringList(PrefsKeys.robotFeatures) ?? + Defaults.robotFeatures) { + try { + _robotFeatures.add(Feature.fromJson(jsonDecode(featureJson))!); + } catch (_) { + // Ignore and skip loading this feature + } + } + widget.telemetry.connectionStatusStream().listen((connected) { if (mounted) { setState(() { @@ -232,6 +245,7 @@ class _TelemetryPageState extends State { targetPose: _targetPose, currentPath: _currentPath, colorScheme: Theme.of(context).colorScheme, + robotFeatures: _robotFeatures, ), ), ), @@ -577,6 +591,7 @@ class TelemetryPainter extends CustomPainter { final Pose2d? targetPose; final List? currentPath; final ColorScheme colorScheme; + final List robotFeatures; static double scale = 1; @@ -588,6 +603,7 @@ class TelemetryPainter extends CustomPainter { this.targetPose, this.currentPath, required this.colorScheme, + required this.robotFeatures, }); @override @@ -623,7 +639,8 @@ class TelemetryPainter extends CustomPainter { scale, canvas, Colors.grey[600]!.withOpacity(0.75), - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); } if (currentPose != null) { @@ -635,7 +652,8 @@ class TelemetryPainter extends CustomPainter { scale, canvas, colorScheme.primary, - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); } } diff --git a/lib/robot_features/circle_feature.dart b/lib/robot_features/circle_feature.dart new file mode 100644 index 00000000..94af467b --- /dev/null +++ b/lib/robot_features/circle_feature.dart @@ -0,0 +1,63 @@ +import 'package:flutter/material.dart'; +import 'package:pathplanner/robot_features/feature.dart'; +import 'package:pathplanner/util/wpimath/geometry.dart'; + +class CircleFeature extends Feature { + Translation2d center; + num radius; + num strokeWidth; + bool filled; + + CircleFeature({ + this.center = const Translation2d(), + this.radius = 0.1, + this.strokeWidth = 0.02, + this.filled = false, + required super.name, + }) : super(type: 'circle'); + + CircleFeature.fromDataJson(Map dataJson, String name) + : this( + center: Translation2d.fromJson(dataJson['center']), + radius: dataJson['radius'], + strokeWidth: dataJson['strokeWidth'], + filled: dataJson['filled'], + name: name, + ); + + @override + Map dataToJson() { + return { + 'center': center.toJson(), + 'radius': radius, + 'strokeWidth': strokeWidth, + 'filled': filled, + }; + } + + @override + void draw(Canvas canvas, double pixelsPerMeter, Color color) { + Paint paint = Paint() + ..style = filled ? PaintingStyle.fill : PaintingStyle.stroke + ..strokeWidth = strokeWidth * pixelsPerMeter + ..color = color; + + Offset centerPixels = + Offset(center.x * pixelsPerMeter, -center.y * pixelsPerMeter); + double radiusPixels = radius * pixelsPerMeter; + + canvas.drawCircle(centerPixels, radiusPixels, paint); + } + + @override + int get hashCode => Object.hash(type, center, radius, strokeWidth, filled); + + @override + bool operator ==(Object other) { + return other is CircleFeature && + other.center == center && + other.radius == radius && + other.strokeWidth == strokeWidth && + other.filled == filled; + } +} diff --git a/lib/robot_features/feature.dart b/lib/robot_features/feature.dart new file mode 100644 index 00000000..36580c4e --- /dev/null +++ b/lib/robot_features/feature.dart @@ -0,0 +1,41 @@ +import 'package:flutter/foundation.dart'; +import 'package:flutter/material.dart'; +import 'package:pathplanner/robot_features/circle_feature.dart'; +import 'package:pathplanner/robot_features/line_feature.dart'; +import 'package:pathplanner/robot_features/rounded_rect_feature.dart'; + +abstract class Feature { + String name; + final String type; + + Feature({required this.name, required this.type}); + + /// Draw the feature on the canvas with the given pixels per meter ratio + /// The canvas should already be transformed to the center of the robot + /// and its rotation. This just needs to draw relative to the robot. + void draw(Canvas canvas, double pixelsPerMeter, Color color); + + Map dataToJson(); + + @nonVirtual + Map toJson() { + return { + 'name': name, + 'type': type, + 'data': dataToJson(), + }; + } + + static Feature? fromJson(Map json) { + String name = json['name']; + String type = json['type']; + Map data = json['data'] ?? {}; + + return switch (type) { + 'rounded_rect' => RoundedRectFeature.fromDataJson(data, name), + 'circle' => CircleFeature.fromDataJson(data, name), + 'line' => LineFeature.fromDataJson(data, name), + _ => null, + }; + } +} diff --git a/lib/robot_features/line_feature.dart b/lib/robot_features/line_feature.dart new file mode 100644 index 00000000..fd21c3fd --- /dev/null +++ b/lib/robot_features/line_feature.dart @@ -0,0 +1,58 @@ +import 'package:flutter/material.dart'; +import 'package:pathplanner/robot_features/feature.dart'; +import 'package:pathplanner/util/wpimath/geometry.dart'; + +class LineFeature extends Feature { + Translation2d start; + Translation2d end; + num strokeWidth; + + LineFeature({ + this.start = const Translation2d(), + this.end = const Translation2d(0.2, 0.0), + this.strokeWidth = 0.02, + required super.name, + }) : super(type: 'line'); + + LineFeature.fromDataJson(Map dataJson, String name) + : this( + start: Translation2d.fromJson(dataJson['start']), + end: Translation2d.fromJson(dataJson['end']), + strokeWidth: dataJson['strokeWidth'], + name: name, + ); + + @override + Map dataToJson() { + return { + 'start': start.toJson(), + 'end': end.toJson(), + 'strokeWidth': strokeWidth, + }; + } + + @override + void draw(Canvas canvas, double pixelsPerMeter, Color color) { + Paint paint = Paint() + ..style = PaintingStyle.stroke + ..strokeWidth = strokeWidth * pixelsPerMeter + ..color = color; + + Offset startPixels = + Offset(start.x * pixelsPerMeter, -start.y * pixelsPerMeter); + Offset endPixels = Offset(end.x * pixelsPerMeter, -end.y * pixelsPerMeter); + + canvas.drawLine(startPixels, endPixels, paint); + } + + @override + int get hashCode => Object.hash(type, start, end, strokeWidth); + + @override + bool operator ==(Object other) { + return other is LineFeature && + other.start == start && + other.end == end && + other.strokeWidth == strokeWidth; + } +} diff --git a/lib/robot_features/rounded_rect_feature.dart b/lib/robot_features/rounded_rect_feature.dart new file mode 100644 index 00000000..0aeaa677 --- /dev/null +++ b/lib/robot_features/rounded_rect_feature.dart @@ -0,0 +1,81 @@ +import 'dart:ui'; + +import 'package:pathplanner/robot_features/feature.dart'; +import 'package:pathplanner/util/wpimath/geometry.dart'; + +class RoundedRectFeature extends Feature { + Translation2d center; + Size size; + num borderRadius; + num strokeWidth; + bool filled; + + RoundedRectFeature({ + this.center = const Translation2d(), + this.size = const Size(0.2, 0.2), + this.borderRadius = 0.05, + this.strokeWidth = 0.02, + this.filled = false, + required super.name, + }) : super(type: 'rounded_rect'); + + RoundedRectFeature.fromDataJson(Map dataJson, String name) + : this( + center: Translation2d.fromJson(dataJson['center']), + size: Size(dataJson['size']['width'], dataJson['size']['length']), + borderRadius: dataJson['borderRadius'], + strokeWidth: dataJson['strokeWidth'], + filled: dataJson['filled'], + name: name, + ); + + @override + Map dataToJson() { + return { + 'center': center.toJson(), + 'size': { + 'width': size.width, + 'length': size.height, + }, + 'borderRadius': borderRadius, + 'strokeWidth': strokeWidth, + 'filled': filled, + }; + } + + @override + void draw(Canvas canvas, double pixelsPerMeter, Color color) { + Paint paint = Paint() + ..style = filled ? PaintingStyle.fill : PaintingStyle.stroke + ..strokeWidth = strokeWidth * pixelsPerMeter + ..color = color; + + Offset centerPixels = + Offset(center.x * pixelsPerMeter, -center.y * pixelsPerMeter); + Size sizePixels = size * pixelsPerMeter; + double borderRadiusPixels = borderRadius * pixelsPerMeter; + + canvas.drawRRect( + RRect.fromRectAndRadius( + Rect.fromCenter( + center: centerPixels, + width: sizePixels.height, + height: sizePixels.width), + Radius.circular(borderRadiusPixels)), + paint); + } + + @override + int get hashCode => + Object.hash(type, center, size, borderRadius, strokeWidth, filled); + + @override + bool operator ==(Object other) { + return other is RoundedRectFeature && + other.center == center && + other.size == size && + other.borderRadius == borderRadius && + other.strokeWidth == strokeWidth && + other.filled == filled; + } +} diff --git a/lib/util/path_painter_util.dart b/lib/util/path_painter_util.dart index e2703e1e..c44955d4 100644 --- a/lib/util/path_painter_util.dart +++ b/lib/util/path_painter_util.dart @@ -1,6 +1,7 @@ import 'dart:math'; import 'package:flutter/material.dart'; +import 'package:pathplanner/robot_features/feature.dart'; import 'package:pathplanner/util/wpimath/geometry.dart'; import 'package:pathplanner/widgets/field_image.dart'; @@ -59,6 +60,7 @@ class PathPainterUtil { Canvas canvas, Color color, Color outlineColor, + List features, {bool showDetails = false}) { Offset center = PathPainterUtil.pointToPixelOffset(pose.translation, scale, fieldImage); @@ -68,6 +70,18 @@ class PathPainterUtil { double length = PathPainterUtil.metersToPixels(robotSize.height, scale, fieldImage); + canvas.save(); + canvas.translate(center.dx, center.dy); + canvas.rotate(-pose.rotation.radians.toDouble()); + + double pixelsPerMeter = + PathPainterUtil.metersToPixels(1.0, scale, fieldImage); + for (Feature f in features) { + f.draw(canvas, pixelsPerMeter, color); + } + + canvas.restore(); + paintRobotOutlinePixels( center, pose.rotation.radians.toDouble(), @@ -164,18 +178,17 @@ class PathPainterUtil { canvas.save(); canvas.translate(center.dx, center.dy); canvas.rotate(-rotationRadians); - canvas.translate(-center.dx, -center.dy); canvas.translate(bumperOffsetPixels.dx, bumperOffsetPixels.dy); canvas.drawRRect( RRect.fromRectAndRadius( Rect.fromCenter( - center: center, + center: Offset.zero, width: robotSizePixels.height, height: robotSizePixels.width), Radius.circular(bumperRadiusPixels)), paint); - Offset frontMiddle = center + Offset(robotSizePixels.height / 2, 0); + Offset frontMiddle = Offset(robotSizePixels.height / 2, 0); // Draw the dot paint.style = PaintingStyle.fill; diff --git a/lib/util/prefs.dart b/lib/util/prefs.dart index dc9d58ad..c5ee6852 100644 --- a/lib/util/prefs.dart +++ b/lib/util/prefs.dart @@ -49,6 +49,7 @@ class PrefsKeys { static const String brModuleY = 'brModuleY'; static const String bumperOffsetX = 'bumperOffsetX'; static const String bumperOffsetY = 'bumperOffsetY'; + static const String robotFeatures = 'robotFeatures'; } class Defaults { @@ -99,4 +100,5 @@ class Defaults { static const double brModuleY = -0.273; static const double bumperOffsetX = 0.0; static const double bumperOffsetY = 0.0; + static const List robotFeatures = []; } diff --git a/lib/widgets/editor/path_painter.dart b/lib/widgets/editor/path_painter.dart index b8386a09..d9942324 100644 --- a/lib/widgets/editor/path_painter.dart +++ b/lib/widgets/editor/path_painter.dart @@ -1,3 +1,4 @@ +import 'dart:convert'; import 'dart:math'; import 'dart:ui'; @@ -5,6 +6,7 @@ import 'package:flutter/material.dart'; import 'package:pathplanner/path/choreo_path.dart'; import 'package:pathplanner/path/point_towards_zone.dart'; import 'package:pathplanner/path/rotation_target.dart'; +import 'package:pathplanner/robot_features/feature.dart'; import 'package:pathplanner/trajectory/config.dart'; import 'package:pathplanner/trajectory/trajectory.dart'; import 'package:pathplanner/path/pathplanner_path.dart'; @@ -40,6 +42,7 @@ class PathPainter extends CustomPainter { late final RobotConfig robotConfig; late final num robotRadius; Animation? previewTime; + final List robotFeatures = []; static double scale = 1; @@ -72,6 +75,15 @@ class PathPainter extends CustomPainter { (robotConfig.bumperSize.height * robotConfig.bumperSize.height)) / 2.0; + for (String featureJson in prefs.getStringList(PrefsKeys.robotFeatures) ?? + Defaults.robotFeatures) { + try { + robotFeatures.add(Feature.fromJson(jsonDecode(featureJson))!); + } catch (_) { + // Ignore and skip loading this feature + } + } + if (simulatedPath != null && animation != null) { previewTime = Tween(begin: 0, end: simulatedPath!.states.last.timeSeconds) @@ -207,16 +219,18 @@ class PathPainter extends CustomPainter { } PathPainterUtil.paintRobotOutline( - Pose2d(state.pose.translation, rotation), - fieldImage, - robotConfig.bumperSize, - robotConfig.bumperOffset, - scale, - canvas, - colorScheme.primary, - showDetails: prefs.getBool(PrefsKeys.showRobotDetails) ?? - Defaults.showRobotDetails, - colorScheme.surfaceContainer); + Pose2d(state.pose.translation, rotation), + fieldImage, + robotConfig.bumperSize, + robotConfig.bumperOffset, + scale, + canvas, + colorScheme.primary, + colorScheme.surfaceContainer, + robotFeatures, + showDetails: prefs.getBool(PrefsKeys.showRobotDetails) ?? + Defaults.showRobotDetails, + ); } } @@ -316,7 +330,8 @@ class PathPainter extends CustomPainter { scale, canvas, color.withOpacity(0.5), - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); } void _paintPathPoints(PathPlannerPath path, Canvas canvas, Color baseColor, @@ -592,7 +607,8 @@ class PathPainter extends CustomPainter { scale, canvas, rotationColor, - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); } } @@ -604,7 +620,8 @@ class PathPainter extends CustomPainter { scale, canvas, Colors.green.withOpacity(0.5), - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); PathPainterUtil.paintRobotOutline( Pose2d(path.waypoints[path.waypoints.length - 1].anchor, @@ -615,7 +632,8 @@ class PathPainter extends CustomPainter { scale, canvas, Colors.red.withOpacity(0.5), - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); } void _paintBreakWarning(Translation2d prevPathEnd, Translation2d pathStart, diff --git a/lib/widgets/robot_config_settings.dart b/lib/widgets/robot_config_settings.dart index cd2700f4..f418a52c 100644 --- a/lib/widgets/robot_config_settings.dart +++ b/lib/widgets/robot_config_settings.dart @@ -1,12 +1,19 @@ +import 'dart:convert'; import 'dart:math'; import 'package:flutter/material.dart'; +import 'package:pathplanner/robot_features/circle_feature.dart'; +import 'package:pathplanner/robot_features/feature.dart'; +import 'package:pathplanner/robot_features/line_feature.dart'; +import 'package:pathplanner/robot_features/rounded_rect_feature.dart'; import 'package:pathplanner/trajectory/dc_motor.dart'; import 'package:pathplanner/util/path_painter_util.dart'; import 'package:pathplanner/util/prefs.dart'; import 'package:pathplanner/util/wpimath/geometry.dart'; import 'package:pathplanner/util/wpimath/units.dart'; +import 'package:pathplanner/widgets/editor/tree_widgets/tree_card_node.dart'; import 'package:pathplanner/widgets/number_text_field.dart'; +import 'package:pathplanner/widgets/renamable_title.dart'; import 'package:shared_preferences/shared_preferences.dart'; class RobotConfigSettings extends StatefulWidget { @@ -39,6 +46,7 @@ class _RobotConfigSettingsState extends State { late String _driveMotor; late num _currentLimit; late List _modulePositions; + final List _features = []; late num _optimalCurrentLimit; late num _maxAccel; @@ -89,6 +97,16 @@ class _RobotConfigSettingsState extends State { widget.prefs.getDouble(PrefsKeys.brModuleY) ?? Defaults.brModuleY), ]; + for (String featureJson + in widget.prefs.getStringList(PrefsKeys.robotFeatures) ?? + Defaults.robotFeatures) { + try { + _features.add(Feature.fromJson(jsonDecode(featureJson))!); + } catch (_) { + // Ignore and skip loading this feature + } + } + _optimalCurrentLimit = _calculateOptimalCurrentLimit(); _maxAccel = _calculateMaxAccel(); _maxAngAccel = _calculateMaxAngAccel(); @@ -109,587 +127,649 @@ class _RobotConfigSettingsState extends State { thumbVisibility: WidgetStateProperty.all(true), ), ), - child: ListView( - padding: const EdgeInsets.only(right: 16), - children: [ - const SizedBox(height: 6), - Row( + child: SingleChildScrollView( + child: Padding( + padding: const EdgeInsets.only(right: 16), + child: Column( + crossAxisAlignment: CrossAxisAlignment.start, children: [ - Expanded( - child: NumberTextField( - initialValue: _mass, - label: 'Robot Mass (KG)', - minValue: 0.0, - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.robotMass, value.toDouble()); - setState(() { - _mass = value; - _optimalCurrentLimit = - _calculateOptimalCurrentLimit(); - _maxAccel = _calculateMaxAccel(); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), - ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _moi, - label: 'Robot MOI (KG*M²)', - minValue: 0.0, - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.robotMOI, value.toDouble()); - setState(() { - _moi = value; - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), - ), - ], - ), - if (!_holonomicMode) ...[ - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _trackwidth, - minValue: 0.01, - label: 'Trackwidth (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.robotTrackwidth, value.toDouble()); - setState(() { - _trackwidth = value; - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, + const SizedBox(height: 6), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _mass, + label: 'Robot Mass (KG)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.robotMass, value.toDouble()); + setState(() { + _mass = value; + _optimalCurrentLimit = + _calculateOptimalCurrentLimit(); + _maxAccel = _calculateMaxAccel(); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), ), - ), - ], - ), - ], - const SizedBox(height: 12), - const Text('Bumpers:'), - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _bumperWidth, - minValue: 0.0, - label: 'Bumper Width (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.robotWidth, value.toDouble()); - setState(() { - _bumperWidth = value; - }); - } - widget.onSettingsChanged(); - }, - ), - ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _bumperLength, - minValue: 0.0, - label: 'Bumper Length (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.robotLength, value.toDouble()); - setState(() { - _bumperLength = value; - }); - } - widget.onSettingsChanged(); - }, - ), - ), - ], - ), - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _bumperOffsetX, - label: 'Bumper Offset X (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.bumperOffsetX, value.toDouble()); - setState(() { - _bumperOffsetX = value; - }); - } - widget.onSettingsChanged(); - }, - ), - ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _bumperOffsetY, - label: 'Bumper Offset Y (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.bumperOffsetY, value.toDouble()); - setState(() { - _bumperOffsetY = value; - }); - } - widget.onSettingsChanged(); - }, - ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _moi, + label: 'Robot MOI (KG*M²)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.robotMOI, value.toDouble()); + setState(() { + _moi = value; + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - ], - ), - const SizedBox(height: 12), - const Text('Module Config:'), - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _wheelRadius, - label: 'Wheel Radius (M)', - minValue: 0.0, - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.driveWheelRadius, value.toDouble()); - setState(() { - _wheelRadius = value; - _optimalCurrentLimit = - _calculateOptimalCurrentLimit(); - _maxAccel = _calculateMaxAccel(); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, + if (!_holonomicMode) ...[ + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _trackwidth, + minValue: 0.01, + label: 'Trackwidth (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.robotTrackwidth, + value.toDouble()); + setState(() { + _trackwidth = value; + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), + ], + const SizedBox(height: 12), + const Text('Bumpers:'), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _bumperWidth, + minValue: 0.0, + label: 'Bumper Width (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.robotWidth, value.toDouble()); + setState(() { + _bumperWidth = value; + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _bumperLength, + minValue: 0.0, + label: 'Bumper Length (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.robotLength, value.toDouble()); + setState(() { + _bumperLength = value; + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _driveGearing, - label: 'Drive Gearing', - minValue: 1.0, - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.driveGearing, value.toDouble()); - setState(() { - _driveGearing = value; - _optimalCurrentLimit = - _calculateOptimalCurrentLimit(); - _maxAccel = _calculateMaxAccel(); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _bumperOffsetX, + label: 'Bumper Offset X (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.bumperOffsetX, value.toDouble()); + setState(() { + _bumperOffsetX = value; + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _bumperOffsetY, + label: 'Bumper Offset Y (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.bumperOffsetY, value.toDouble()); + setState(() { + _bumperOffsetY = value; + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - ], - ), - const SizedBox(height: 12), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _maxDriveSpeed, - label: 'True Max Drive Speed (M/S)', - minValue: 0.0, - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.maxDriveSpeed, value.toDouble()); - setState(() { - _maxDriveSpeed = value; - _optimalCurrentLimit = - _calculateOptimalCurrentLimit(); - _maxAccel = _calculateMaxAccel(); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), + const SizedBox(height: 12), + const Text('Module Config:'), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _wheelRadius, + label: 'Wheel Radius (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.driveWheelRadius, + value.toDouble()); + setState(() { + _wheelRadius = value; + _optimalCurrentLimit = + _calculateOptimalCurrentLimit(); + _maxAccel = _calculateMaxAccel(); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _driveGearing, + label: 'Drive Gearing', + minValue: 1.0, + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.driveGearing, value.toDouble()); + setState(() { + _driveGearing = value; + _optimalCurrentLimit = + _calculateOptimalCurrentLimit(); + _maxAccel = _calculateMaxAccel(); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _wheelCOF, - minValue: 0.0, - label: 'Wheel COF', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.wheelCOF, value.toDouble()); - setState(() { - _wheelCOF = value; - _optimalCurrentLimit = - _calculateOptimalCurrentLimit(); - _maxAccel = _calculateMaxAccel(); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), + const SizedBox(height: 12), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _maxDriveSpeed, + label: 'True Max Drive Speed (M/S)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.maxDriveSpeed, value.toDouble()); + setState(() { + _maxDriveSpeed = value; + _optimalCurrentLimit = + _calculateOptimalCurrentLimit(); + _maxAccel = _calculateMaxAccel(); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _wheelCOF, + minValue: 0.0, + label: 'Wheel COF', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.wheelCOF, value.toDouble()); + setState(() { + _wheelCOF = value; + _optimalCurrentLimit = + _calculateOptimalCurrentLimit(); + _maxAccel = _calculateMaxAccel(); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - ], - ), - Row( - crossAxisAlignment: CrossAxisAlignment.start, - children: [ - Expanded( - child: Column( - crossAxisAlignment: CrossAxisAlignment.start, - children: [ - Stack( + Row( + crossAxisAlignment: CrossAxisAlignment.start, + children: [ + Expanded( + child: Column( + crossAxisAlignment: CrossAxisAlignment.start, children: [ - Column( + Stack( children: [ - const SizedBox(height: 9), - SizedBox( - height: 49, - child: Padding( - padding: const EdgeInsets.symmetric( - vertical: 4), - child: Container( - decoration: BoxDecoration( - borderRadius: - BorderRadius.circular(8), - border: Border.all( - color: colorScheme.outline), - ), - child: ExcludeFocus( - child: ButtonTheme( - alignedDropdown: true, - child: DropdownButton( + Column( + children: [ + const SizedBox(height: 9), + SizedBox( + height: 49, + child: Padding( + padding: const EdgeInsets.symmetric( + vertical: 4), + child: Container( + decoration: BoxDecoration( borderRadius: BorderRadius.circular(8), - value: _driveMotor, - isExpanded: true, - underline: Container(), - menuMaxHeight: 250, - icon: const Icon( - Icons.arrow_drop_down), - style: TextStyle( - fontSize: 14, - color: colorScheme.onSurface), - onChanged: (String? newValue) { - if (newValue != null) { - setState(() { - _driveMotor = newValue; - _optimalCurrentLimit = - _calculateOptimalCurrentLimit(); - _maxAccel = - _calculateMaxAccel(); - _maxAngAccel = - _calculateMaxAngAccel(); - }); - widget.prefs.setString( - PrefsKeys.driveMotor, - _driveMotor); - widget.onSettingsChanged(); - } - }, - items: const [ - DropdownMenuItem( - value: 'krakenX60', - child: Text('Kraken X60'), - ), - DropdownMenuItem( - value: 'krakenX60FOC', - child: Text('Kraken X60 FOC'), - ), - DropdownMenuItem( - value: 'falcon500', - child: Text('Falcon 500'), - ), - DropdownMenuItem( - value: 'falcon500FOC', - child: Text('Falcon 500 FOC'), - ), - DropdownMenuItem( - value: 'vortex', - child: Text('NEO Vortex'), - ), - DropdownMenuItem( - value: 'NEO', - child: Text('NEO'), - ), - DropdownMenuItem( - value: 'CIM', - child: Text('CIM'), - ), - DropdownMenuItem( - value: 'miniCIM', - child: Text('MiniCIM'), + border: Border.all( + color: colorScheme.outline), + ), + child: ExcludeFocus( + child: ButtonTheme( + alignedDropdown: true, + child: DropdownButton( + borderRadius: + BorderRadius.circular(8), + value: _driveMotor, + isExpanded: true, + underline: Container(), + menuMaxHeight: 250, + icon: const Icon( + Icons.arrow_drop_down), + style: TextStyle( + fontSize: 14, + color: colorScheme + .onSurface), + onChanged: + (String? newValue) { + if (newValue != null) { + setState(() { + _driveMotor = newValue; + _optimalCurrentLimit = + _calculateOptimalCurrentLimit(); + _maxAccel = + _calculateMaxAccel(); + _maxAngAccel = + _calculateMaxAngAccel(); + }); + widget.prefs.setString( + PrefsKeys.driveMotor, + _driveMotor); + widget + .onSettingsChanged(); + } + }, + items: const [ + DropdownMenuItem( + value: 'krakenX60', + child: Text('Kraken X60'), + ), + DropdownMenuItem( + value: 'krakenX60FOC', + child: Text( + 'Kraken X60 FOC'), + ), + DropdownMenuItem( + value: 'falcon500', + child: Text('Falcon 500'), + ), + DropdownMenuItem( + value: 'falcon500FOC', + child: Text( + 'Falcon 500 FOC'), + ), + DropdownMenuItem( + value: 'vortex', + child: Text('NEO Vortex'), + ), + DropdownMenuItem( + value: 'NEO', + child: Text('NEO'), + ), + DropdownMenuItem( + value: 'CIM', + child: Text('CIM'), + ), + DropdownMenuItem( + value: 'miniCIM', + child: Text('MiniCIM'), + ), + ], ), - ], + ), ), ), ), ), + ], + ), + Padding( + padding: + const EdgeInsets.only(left: 2, top: 12), + child: Container( + width: 78, + height: 3, + color: colorScheme.surface, ), ), - ], - ), - Padding( - padding: - const EdgeInsets.only(left: 2, top: 12), - child: Container( - width: 78, - height: 3, - color: colorScheme.surface, - ), - ), - Padding( - padding: const EdgeInsets.only(left: 8, top: 3), - child: Text( - 'Drive Motor', - style: TextStyle( - fontSize: 12, - color: colorScheme.onSurfaceVariant, + Padding( + padding: + const EdgeInsets.only(left: 8, top: 3), + child: Text( + 'Drive Motor', + style: TextStyle( + fontSize: 12, + color: colorScheme.onSurfaceVariant, + ), + ), ), - ), + ], ), ], ), - ], - ), - ), - const SizedBox(width: 8), - Expanded( - child: Padding( - padding: const EdgeInsets.only(top: 12.0), - child: NumberTextField( - initialValue: _currentLimit, - label: 'Drive Current Limit (A)', - minValue: 0.0, - precision: 0, - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.driveCurrentLimit, - value.roundToDouble()); - setState(() { - _currentLimit = value.roundToDouble(); - _maxAccel = _calculateMaxAccel(); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), - ), - ), - ], - ), - if (_holonomicMode) ...[ - const SizedBox(height: 12), - const Text('Module Offsets:'), - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _modulePositions[0].x, - minValue: 0.0, - label: 'Front Left X (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.flModuleX, value.toDouble()); - setState(() { - _modulePositions[0] = - Translation2d(value, _modulePositions[0].y); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, ), - ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _modulePositions[0].y, - minValue: 0.0, - label: 'Front Left Y (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.flModuleY, value.toDouble()); - setState(() { - _modulePositions[0] = - Translation2d(_modulePositions[0].x, value); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), - ), - ], - ), - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _modulePositions[1].x, - minValue: 0.0, - label: 'Front Right X (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.frModuleX, value.toDouble()); - setState(() { - _modulePositions[1] = - Translation2d(value, _modulePositions[1].y); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, + const SizedBox(width: 8), + Expanded( + child: Padding( + padding: const EdgeInsets.only(top: 12.0), + child: NumberTextField( + initialValue: _currentLimit, + label: 'Drive Current Limit (A)', + minValue: 0.0, + precision: 0, + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.driveCurrentLimit, + value.roundToDouble()); + setState(() { + _currentLimit = value.roundToDouble(); + _maxAccel = _calculateMaxAccel(); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), ), + ], + ), + if (_holonomicMode) ...[ + const SizedBox(height: 12), + const Text('Module Offsets:'), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _modulePositions[0].x, + minValue: 0.0, + label: 'Front Left X (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.flModuleX, value.toDouble()); + setState(() { + _modulePositions[0] = Translation2d( + value, _modulePositions[0].y); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _modulePositions[0].y, + minValue: 0.0, + label: 'Front Left Y (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.flModuleY, value.toDouble()); + setState(() { + _modulePositions[0] = Translation2d( + _modulePositions[0].x, value); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _modulePositions[1].y, - maxValue: 0.0, - label: 'Front Right Y (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.frModuleY, value.toDouble()); - setState(() { - _modulePositions[1] = - Translation2d(_modulePositions[1].x, value); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _modulePositions[1].x, + minValue: 0.0, + label: 'Front Right X (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.frModuleX, value.toDouble()); + setState(() { + _modulePositions[1] = Translation2d( + value, _modulePositions[1].y); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _modulePositions[1].y, + maxValue: 0.0, + label: 'Front Right Y (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.frModuleY, value.toDouble()); + setState(() { + _modulePositions[1] = Translation2d( + _modulePositions[1].x, value); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - ], - ), - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _modulePositions[2].x, - maxValue: 0.0, - label: 'Back Left X (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.blModuleX, value.toDouble()); - setState(() { - _modulePositions[2] = - Translation2d(value, _modulePositions[2].y); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _modulePositions[2].x, + maxValue: 0.0, + label: 'Back Left X (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.blModuleX, value.toDouble()); + setState(() { + _modulePositions[2] = Translation2d( + value, _modulePositions[2].y); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _modulePositions[2].y, + minValue: 0.0, + label: 'Back Left Y (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.blModuleY, value.toDouble()); + setState(() { + _modulePositions[2] = Translation2d( + _modulePositions[2].x, value); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _modulePositions[2].y, - minValue: 0.0, - label: 'Back Left Y (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.blModuleY, value.toDouble()); - setState(() { - _modulePositions[2] = - Translation2d(_modulePositions[2].x, value); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, - ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: _modulePositions[3].x, + maxValue: 0.0, + label: 'Back Right X (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.brModuleX, value.toDouble()); + setState(() { + _modulePositions[3] = Translation2d( + value, _modulePositions[3].y); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: _modulePositions[3].y, + maxValue: 0.0, + label: 'Back Right Y (M)', + onSubmitted: (value) { + if (value != null) { + widget.prefs.setDouble( + PrefsKeys.brModuleY, value.toDouble()); + setState(() { + _modulePositions[3] = Translation2d( + _modulePositions[3].x, value); + _maxAngAccel = _calculateMaxAngAccel(); + }); + } + widget.onSettingsChanged(); + }, + ), + ), + ], ), ], - ), - const SizedBox(height: 8), - Row( - children: [ - Expanded( - child: NumberTextField( - initialValue: _modulePositions[3].x, - maxValue: 0.0, - label: 'Back Right X (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.brModuleX, value.toDouble()); - setState(() { - _modulePositions[3] = - Translation2d(value, _modulePositions[3].y); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } - widget.onSettingsChanged(); - }, + const SizedBox(height: 8), + Row( + crossAxisAlignment: CrossAxisAlignment.start, + children: [ + const Padding( + padding: EdgeInsets.only(top: 8), + child: Text('Robot Features:'), ), - ), - const SizedBox(width: 8), - Expanded( - child: NumberTextField( - initialValue: _modulePositions[3].y, - maxValue: 0.0, - label: 'Back Right Y (M)', - onSubmitted: (value) { - if (value != null) { - widget.prefs.setDouble( - PrefsKeys.brModuleY, value.toDouble()); - setState(() { - _modulePositions[3] = - Translation2d(_modulePositions[3].x, value); - _maxAngAccel = _calculateMaxAngAccel(); - }); - } + PopupMenuButton( + tooltip: 'Add Feature', + icon: Icon(Icons.add, color: colorScheme.primary), + itemBuilder: (context) => const [ + PopupMenuItem( + value: 'rounded_rect', + child: Text('Rectangle'), + ), + PopupMenuItem( + value: 'circle', + child: Text('Circle'), + ), + PopupMenuItem( + value: 'line', + child: Text('Line'), + ), + ], + onSelected: (value) { + setState(() { + switch (value) { + case 'rounded_rect': + _features.add( + RoundedRectFeature(name: 'Rectangle')); + break; + case 'circle': + _features.add(CircleFeature(name: 'Circle')); + break; + case 'line': + _features.add(LineFeature(name: 'Line')); + break; + } + }); + _saveFeatures(); widget.onSettingsChanged(); }, ), - ), - ], - ), - ], - ], + ], + ), + const SizedBox(height: 4), + for (int i = 0; i < _features.length; i++) + _buildFeatureWidget(i, colorScheme), + ], + ), + ), ), ), ), @@ -712,6 +792,7 @@ class _RobotConfigSettingsState extends State { bumperOffsetX: _bumperOffsetX, bumperOffsetY: _bumperOffsetY, modulePositions: _holonomicMode ? _modulePositions : [], + features: _features, ), ), ), @@ -845,6 +926,440 @@ class _RobotConfigSettingsState extends State { ); } + Widget _buildFeatureWidget(int idx, ColorScheme colorScheme) { + return switch (_features[idx].type) { + 'rounded_rect' => _buildRectFeatureCard(idx, colorScheme), + 'circle' => _buildCircleFeatureCard(idx, colorScheme), + 'line' => _buildLineFeatureCard(idx, colorScheme), + _ => Container(), + }; + } + + Widget _buildRectFeatureCard(int idx, ColorScheme colorScheme) { + RoundedRectFeature f = _features[idx] as RoundedRectFeature; + + return TreeCardNode( + title: Row( + children: [ + RenamableTitle( + title: f.name, + onRename: (value) { + if (value.isNotEmpty) { + setState(() { + f.name = value; + }); + } + }, + ), + Expanded(child: Container()), + ], + ), + trailing: Tooltip( + message: 'Delete Feature', + waitDuration: const Duration(seconds: 1), + child: IconButton( + icon: const Icon(Icons.delete_forever), + color: colorScheme.error, + onPressed: () { + setState(() { + _features.removeAt(idx); + }); + _saveFeatures(); + widget.onSettingsChanged(); + }, + ), + ), + children: [ + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.center.x, + label: 'Center X (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.center = Translation2d(value, f.center.y); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: f.center.y, + label: 'Center Y (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.center = Translation2d(f.center.x, value); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.size.width, + label: 'Width (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + setState(() { + f.size = Size(value.toDouble(), f.size.height); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: f.size.height, + label: 'Length (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + setState(() { + f.size = Size(f.size.width, value.toDouble()); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.borderRadius, + label: 'Border Radius (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + setState(() { + f.borderRadius = value; + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: f.strokeWidth, + label: 'Stroke Width (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + setState(() { + f.strokeWidth = value; + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + const SizedBox(height: 8), + FilterChip.elevated( + label: const Text('Filled'), + selected: f.filled, + backgroundColor: colorScheme.surfaceContainerLow, + onSelected: (value) { + setState(() { + f.filled = value; + }); + _saveFeatures(); + widget.onSettingsChanged(); + }, + ), + ], + ); + } + + Widget _buildCircleFeatureCard(int idx, ColorScheme colorScheme) { + CircleFeature f = _features[idx] as CircleFeature; + + return TreeCardNode( + title: Row( + children: [ + RenamableTitle( + title: f.name, + onRename: (value) { + if (value.isNotEmpty) { + setState(() { + f.name = value; + }); + } + }, + ), + Expanded(child: Container()), + ], + ), + trailing: Tooltip( + message: 'Delete Feature', + waitDuration: const Duration(seconds: 1), + child: IconButton( + icon: const Icon(Icons.delete_forever), + color: colorScheme.error, + onPressed: () { + setState(() { + _features.removeAt(idx); + }); + _saveFeatures(); + widget.onSettingsChanged(); + }, + ), + ), + children: [ + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.center.x, + label: 'Center X (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.center = Translation2d(value, f.center.y); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: f.center.y, + label: 'Center Y (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.center = Translation2d(f.center.x, value); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.radius, + label: 'Radius (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + setState(() { + f.radius = value; + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: f.strokeWidth, + label: 'Stroke Width (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + setState(() { + f.strokeWidth = value; + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + const SizedBox(height: 8), + FilterChip.elevated( + label: const Text('Filled'), + selected: f.filled, + backgroundColor: colorScheme.surfaceContainerLow, + onSelected: (value) { + setState(() { + f.filled = value; + }); + _saveFeatures(); + widget.onSettingsChanged(); + }, + ), + ], + ); + } + + Widget _buildLineFeatureCard(int idx, ColorScheme colorScheme) { + LineFeature f = _features[idx] as LineFeature; + + return TreeCardNode( + title: Row( + children: [ + RenamableTitle( + title: f.name, + onRename: (value) { + if (value.isNotEmpty) { + setState(() { + f.name = value; + }); + } + }, + ), + Expanded(child: Container()), + ], + ), + trailing: Tooltip( + message: 'Delete Feature', + waitDuration: const Duration(seconds: 1), + child: IconButton( + icon: const Icon(Icons.delete_forever), + color: colorScheme.error, + onPressed: () { + setState(() { + _features.removeAt(idx); + }); + _saveFeatures(); + widget.onSettingsChanged(); + }, + ), + ), + children: [ + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.start.x, + label: 'Start X (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.start = Translation2d(value, f.start.y); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: f.start.y, + label: 'Start Y (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.start = Translation2d(f.start.x, value); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.end.x, + label: 'End X (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.end = Translation2d(value, f.end.y); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + const SizedBox(width: 8), + Expanded( + child: NumberTextField( + initialValue: f.end.y, + label: 'End Y (M)', + onSubmitted: (value) { + if (value != null) { + setState(() { + f.end = Translation2d(f.end.x, value); + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + const SizedBox(height: 8), + Row( + children: [ + Expanded( + child: NumberTextField( + initialValue: f.strokeWidth, + label: 'Stroke Width (M)', + minValue: 0.0, + onSubmitted: (value) { + if (value != null) { + setState(() { + f.strokeWidth = value; + }); + _saveFeatures(); + widget.onSettingsChanged(); + } + }, + ), + ), + ], + ), + ], + ); + } + + void _saveFeatures() { + widget.prefs.setStringList(PrefsKeys.robotFeatures, [ + for (Feature f in _features) jsonEncode(f.toJson()), + ]); + } + num _calculateOptimalCurrentLimit() { final int numModules = _holonomicMode ? _modulePositions.length : 2; final int numMotors = _holonomicMode ? 1 : 2; @@ -923,6 +1438,7 @@ class _RobotPainter extends CustomPainter { final num bumperOffsetX; final num bumperOffsetY; final List modulePositions; + final List features; const _RobotPainter({ required this.colorScheme, @@ -931,6 +1447,7 @@ class _RobotPainter extends CustomPainter { required this.modulePositions, required this.bumperOffsetX, required this.bumperOffsetY, + required this.features, }); @override @@ -953,13 +1470,17 @@ class _RobotPainter extends CustomPainter { canvas.drawCircle(Offset.zero, 1.5, paint); + for (final feature in features) { + feature.draw(canvas, pixelsPerMeter, colorScheme.primary); + } + PathPainterUtil.paintRobotOutlinePixels( Offset.zero, 0.0, Size(bumperWidth * pixelsPerMeter, bumperLength * pixelsPerMeter), bumperOffsetPixels, 8, - 4.0, + 0.02 * pixelsPerMeter, 0.075 * pixelsPerMeter, canvas, colorScheme.primary, diff --git a/lib/widgets/trajectory_render.dart b/lib/widgets/trajectory_render.dart index d73499d1..948c6cd2 100644 --- a/lib/widgets/trajectory_render.dart +++ b/lib/widgets/trajectory_render.dart @@ -1,7 +1,11 @@ +import 'dart:convert'; + import 'package:flutter/material.dart'; +import 'package:pathplanner/robot_features/feature.dart'; import 'package:pathplanner/trajectory/config.dart'; import 'package:pathplanner/trajectory/trajectory.dart'; import 'package:pathplanner/util/path_painter_util.dart'; +import 'package:pathplanner/util/prefs.dart'; import 'package:pathplanner/util/wpimath/geometry.dart'; import 'package:pathplanner/widgets/field_image.dart'; import 'package:shared_preferences/shared_preferences.dart'; @@ -53,6 +57,7 @@ class TrajectoryPainter extends CustomPainter { final PathPlannerTrajectory trajectory; final SharedPreferences prefs; final num? sampleTime; + final List robotFeatures = []; late final RobotConfig robotConfig; @@ -66,6 +71,15 @@ class TrajectoryPainter extends CustomPainter { required this.sampleTime, }) { robotConfig = RobotConfig.fromPrefs(prefs); + + for (String featureJson in prefs.getStringList(PrefsKeys.robotFeatures) ?? + Defaults.robotFeatures) { + try { + robotFeatures.add(Feature.fromJson(jsonDecode(featureJson))!); + } catch (_) { + // Ignore and skip loading this feature + } + } } @override @@ -90,7 +104,8 @@ class TrajectoryPainter extends CustomPainter { scale, canvas, Colors.green[700]!, - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); PathPainterUtil.paintRobotOutline( Pose2d(trajectory.states.last.pose.translation, trajectory.states.last.pose.rotation), @@ -100,7 +115,8 @@ class TrajectoryPainter extends CustomPainter { scale, canvas, Colors.red[700]!, - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); } else { TrajectoryState state = trajectory.sample(sampleTime!); Rotation2d rotation = state.pose.rotation; @@ -147,7 +163,8 @@ class TrajectoryPainter extends CustomPainter { colorScheme.brightness == Brightness.dark ? colorScheme.primary : colorScheme.secondary, - colorScheme.surfaceContainer); + colorScheme.surfaceContainer, + robotFeatures); } } diff --git a/test/robot_features/feature_test.dart b/test/robot_features/feature_test.dart new file mode 100644 index 00000000..4ae51a55 --- /dev/null +++ b/test/robot_features/feature_test.dart @@ -0,0 +1,31 @@ +import 'package:flutter_test/flutter_test.dart'; +import 'package:pathplanner/robot_features/circle_feature.dart'; +import 'package:pathplanner/robot_features/feature.dart'; +import 'package:pathplanner/robot_features/line_feature.dart'; +import 'package:pathplanner/robot_features/rounded_rect_feature.dart'; + +void main() { + test('rounded rect to/from json', () { + final rect1 = RoundedRectFeature(name: 'test'); + final rect2 = Feature.fromJson(rect1.toJson()); + + expect(rect2, rect1); + expect(rect2.hashCode, rect1.hashCode); + }); + + test('circle to/from json', () { + final circ1 = CircleFeature(name: 'test'); + final circ2 = Feature.fromJson(circ1.toJson()); + + expect(circ2, circ1); + expect(circ2.hashCode, circ1.hashCode); + }); + + test('line to/from json', () { + final line1 = LineFeature(name: 'test'); + final line2 = Feature.fromJson(line1.toJson()); + + expect(line2, line1); + expect(line2.hashCode, line1.hashCode); + }); +} diff --git a/test/widgets/robot_config_settings_test.dart b/test/widgets/robot_config_settings_test.dart index 8de30d7e..3a7b4263 100644 --- a/test/widgets/robot_config_settings_test.dart +++ b/test/widgets/robot_config_settings_test.dart @@ -1,6 +1,12 @@ +import 'dart:convert'; + import 'package:flutter/material.dart'; import 'package:flutter_test/flutter_test.dart'; +import 'package:pathplanner/robot_features/circle_feature.dart'; +import 'package:pathplanner/robot_features/line_feature.dart'; +import 'package:pathplanner/robot_features/rounded_rect_feature.dart'; import 'package:pathplanner/util/prefs.dart'; +import 'package:pathplanner/widgets/editor/tree_widgets/tree_card_node.dart'; import 'package:pathplanner/widgets/number_text_field.dart'; import 'package:pathplanner/widgets/robot_config_settings.dart'; import 'package:shared_preferences/shared_preferences.dart'; @@ -616,4 +622,616 @@ void main() { expect(prefs.getDouble(PrefsKeys.brModuleY), -0.1); }); }); + + group('robot features', () { + testWidgets('add/delete rounded rect feature', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final addButton = find.byTooltip('Add Feature'); + expect(addButton, findsOneWidget); + + await widgetTester.tap(addButton); + await widgetTester.pumpAndSettle(); + + final rrectOption = find.text('Rectangle'); + expect(rrectOption, findsOneWidget); + + await widgetTester.tap(rrectOption); + await widgetTester.pumpAndSettle(); + + final featureCard = find.widgetWithText(TreeCardNode, 'Rectangle'); + expect(featureCard, findsOneWidget); + + final deleteButton = find.byTooltip('Delete Feature'); + expect(deleteButton, findsOneWidget); + + await widgetTester.tap(deleteButton); + await widgetTester.pumpAndSettle(); + + expect(featureCard, findsNothing); + }); + + testWidgets('add/delete circle feature', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final addButton = find.byTooltip('Add Feature'); + expect(addButton, findsOneWidget); + + await widgetTester.tap(addButton); + await widgetTester.pumpAndSettle(); + + final circOption = find.text('Circle'); + expect(circOption, findsOneWidget); + + await widgetTester.tap(circOption); + await widgetTester.pumpAndSettle(); + + final featureCard = find.widgetWithText(TreeCardNode, 'Circle'); + expect(featureCard, findsOneWidget); + + final deleteButton = find.byTooltip('Delete Feature'); + expect(deleteButton, findsOneWidget); + + await widgetTester.tap(deleteButton); + await widgetTester.pumpAndSettle(); + + expect(featureCard, findsNothing); + }); + + testWidgets('add/delete line feature', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final addButton = find.byTooltip('Add Feature'); + expect(addButton, findsOneWidget); + + await widgetTester.tap(addButton); + await widgetTester.pumpAndSettle(); + + final lineOption = find.text('Line'); + expect(lineOption, findsOneWidget); + + await widgetTester.tap(lineOption); + await widgetTester.pumpAndSettle(); + + final featureCard = find.widgetWithText(TreeCardNode, 'Line'); + expect(featureCard, findsOneWidget); + + final deleteButton = find.byTooltip('Delete Feature'); + expect(deleteButton, findsOneWidget); + + await widgetTester.tap(deleteButton); + await widgetTester.pumpAndSettle(); + + expect(featureCard, findsNothing); + }); + + group('rounded rect feature', () { + setUp(() { + prefs.setStringList(PrefsKeys.robotFeatures, [ + jsonEncode(RoundedRectFeature(name: 'test').toJson()), + ]); + }); + + testWidgets('center x text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Center X (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('center y text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Center Y (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('width text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Width (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('length text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Length (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('border radius text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = + find.widgetWithText(NumberTextField, 'Border Radius (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('stroke width text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = + find.widgetWithText(NumberTextField, 'Stroke Width (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('filled chip', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(FilterChip, 'Filled'); + expect(textField, findsOneWidget); + + await widgetTester.tap(textField); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + }); + + group('circle feature', () { + setUp(() { + prefs.setStringList(PrefsKeys.robotFeatures, [ + jsonEncode(CircleFeature(name: 'test').toJson()), + ]); + }); + + testWidgets('center x text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Center X (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('center y text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Center Y (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('radius text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Radius (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('stroke width text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = + find.widgetWithText(NumberTextField, 'Stroke Width (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('filled chip', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(FilterChip, 'Filled'); + expect(textField, findsOneWidget); + + await widgetTester.tap(textField); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + }); + + group('line feature', () { + setUp(() { + prefs.setStringList(PrefsKeys.robotFeatures, [ + jsonEncode(LineFeature(name: 'test').toJson()), + ]); + }); + + testWidgets('start x text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Start X (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('start y text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'Start Y (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('end x text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'End X (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('end y text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = find.widgetWithText(NumberTextField, 'End Y (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + + testWidgets('stroke width text field', (widgetTester) async { + await widgetTester.binding.setSurfaceSize(const Size(1280, 1200)); + + await widgetTester.pumpWidget(MaterialApp( + home: Scaffold( + body: RobotConfigSettings( + onSettingsChanged: () => settingsChanged = true, + prefs: prefs, + ), + ), + )); + + final treeCard = find.widgetWithText(TreeCardNode, 'test'); + expect(treeCard, findsOneWidget); + + await widgetTester.tap(treeCard); + await widgetTester.pumpAndSettle(); + + final textField = + find.widgetWithText(NumberTextField, 'Stroke Width (M)'); + expect(textField, findsOneWidget); + + await widgetTester.enterText(textField, '0.5'); + await widgetTester.testTextInput.receiveAction(TextInputAction.done); + await widgetTester.pump(); + + expect(settingsChanged, isTrue); + }); + }); + }); }