Skip to content

Commit

Permalink
Show preview starting state on the field (#523)
Browse files Browse the repository at this point in the history
  • Loading branch information
mjansen4857 authored Dec 23, 2023
1 parent f88468f commit 69c96e9
Show file tree
Hide file tree
Showing 3 changed files with 96 additions and 5 deletions.
11 changes: 11 additions & 0 deletions lib/widgets/editor/path_painter.dart
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,17 @@ class PathPainter extends CustomPainter {
for (int w = 0; w < paths[i].waypoints.length; w++) {
_paintWaypoint(paths[i], canvas, scale, w);
}

if (paths[i].previewStartingState != null) {
PathPainterUtil.paintRobotOutline(
paths[i].waypoints.first.anchor,
paths[i].previewStartingState!.rotation,
fieldImage,
robotSize,
scale,
canvas,
Colors.green.withOpacity(0.5));
}
} else {
_paintWaypoint(paths[i], canvas, scale, 0);
_paintWaypoint(paths[i], canvas, scale, paths[i].waypoints.length - 1);
Expand Down
43 changes: 38 additions & 5 deletions lib/widgets/editor/split_path_editor.dart
Original file line number Diff line number Diff line change
Expand Up @@ -198,10 +198,17 @@ class _SplitPathEditorState extends State<SplitPathEditor>
PathPainterUtil.uiPointSizeToPixels(
15, PathPainter.scale, widget.fieldImage));
// This is a little bit stupid but whatever
for (int i = -1; i < widget.path.rotationTargets.length; i++) {
for (int i = -2; i < widget.path.rotationTargets.length; i++) {
num rotation;
Point pos;
if (i == -1) {
if (i == -2) {
if (widget.path.previewStartingState == null) {
continue;
}

rotation = widget.path.previewStartingState!.rotation;
pos = widget.path.waypoints.first.anchor;
} else if (i == -1) {
rotation = widget.path.goalEndState.rotation;
pos = widget.path.waypoints.last.anchor;
} else {
Expand Down Expand Up @@ -283,7 +290,9 @@ class _SplitPathEditorState extends State<SplitPathEditor>
});
} else if (_draggedRotationIdx != null) {
Point pos;
if (_draggedRotationIdx == -1) {
if (_draggedRotationIdx == -2) {
pos = widget.path.waypoints.first.anchor;
} else if (_draggedRotationIdx == -1) {
pos = widget.path.waypoints.last.anchor;
} else {
int pointIdx = (widget
Expand All @@ -301,7 +310,9 @@ class _SplitPathEditorState extends State<SplitPathEditor>
num rotationDeg = (rotation * 180 / pi);

setState(() {
if (_draggedRotationIdx == -1) {
if (_draggedRotationIdx == -2) {
widget.path.previewStartingState!.rotation = rotationDeg;
} else if (_draggedRotationIdx == -1) {
widget.path.goalEndState.rotation = rotationDeg;
} else {
widget.path.rotationTargets[_draggedRotationIdx!]
Expand Down Expand Up @@ -344,7 +355,29 @@ class _SplitPathEditorState extends State<SplitPathEditor>
));
_draggedPoint = null;
} else if (_draggedRotationIdx != null) {
if (_draggedRotationIdx == -1) {
if (_draggedRotationIdx == -2) {
num endRotation =
widget.path.previewStartingState!.rotation;
widget.undoStack.add(Change(
_dragRotationOldValue,
() {
setState(() {
widget.path.previewStartingState!.rotation =
endRotation;
widget.path.generateAndSavePath();
_simulatePath();
});
},
(oldValue) {
setState(() {
widget.path.previewStartingState!.rotation =
oldValue!;
widget.path.generateAndSavePath();
_simulatePath();
});
},
));
} else if (_draggedRotationIdx == -1) {
num endRotation = widget.path.goalEndState.rotation;
widget.undoStack.add(Change(
_dragRotationOldValue,
Expand Down
47 changes: 47 additions & 0 deletions test/widgets/editor/split_path_editor_test.dart
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ import 'package:pathplanner/path/constraints_zone.dart';
import 'package:pathplanner/path/event_marker.dart';
import 'package:pathplanner/path/path_constraints.dart';
import 'package:pathplanner/path/pathplanner_path.dart';
import 'package:pathplanner/path/preview_starting_state.dart';
import 'package:pathplanner/path/rotation_target.dart';
import 'package:pathplanner/util/path_painter_util.dart';
import 'package:pathplanner/util/prefs.dart';
Expand Down Expand Up @@ -363,6 +364,52 @@ void main() {
expect(path.goalEndState.rotation, closeTo(0, 0.1));
});

testWidgets('drag preview starting state rotation', (widgetTester) async {
await widgetTester.binding.setSurfaceSize(const Size(1280, 720));

path.previewStartingState = PreviewStartingState();

await widgetTester.pumpWidget(MaterialApp(
home: Scaffold(
body: SplitPathEditor(
prefs: prefs,
path: path,
fieldImage: FieldImage.defaultField,
undoStack: undoStack,
),
),
));

Point targetPos = path.waypoints.first.anchor;
var dragLocation = PathPainterUtil.pointToPixelOffset(
targetPos + const Point(0.5, 0.0),
PathPainter.scale,
FieldImage.defaultField) +
const Offset(48, 48) + // Add 48 for padding
const Offset(2.0, 28.0); // Some weird buffer going on
var halfMeterPixels = PathPainterUtil.metersToPixels(
0.5, PathPainter.scale, FieldImage.defaultField);

var gesture = await widgetTester.startGesture(dragLocation,
kind: PointerDeviceKind.mouse);
await widgetTester.pump();

for (int i = 0; i <= halfMeterPixels.ceil(); i++) {
await gesture.moveBy(const Offset(-1, -1.5));
await widgetTester.pump();
}

await gesture.up();
await widgetTester.pumpAndSettle();

expect(path.previewStartingState!.rotation, closeTo(90, 1.0));

undoStack.undo();
await widgetTester.pumpAndSettle();

expect(path.previewStartingState!.rotation, closeTo(0, 0.1));
});

testWidgets('delete waypoint', (widgetTester) async {
await widgetTester.binding.setSurfaceSize(const Size(1280, 720));

Expand Down

0 comments on commit 69c96e9

Please sign in to comment.