diff --git a/autonomous/auto_base.py b/autonomous/auto_base.py index c58f31dc..0037a37a 100644 --- a/autonomous/auto_base.py +++ b/autonomous/auto_base.py @@ -182,3 +182,129 @@ def shooting_algae(self) -> None: if not self.algae_shooter.is_executing: self.next_state("tracking_trajectory") + + +class AutoBaseNoBalls(AutonomousStateMachine): + chassis: ChassisComponent + + field: wpilib.Field2d + + DISTANCE_TOLERANCE = 0.1 # metres + ANGLE_TOLERANCE = math.radians(3) + CORAL_DISTANCE_TOLERANCE = 0.2 # metres + TRANSLATIONAL_SPEED_TOLERANCE = 0.2 + ROTATIONAL_SPEED_TOLERANCE = 0.1 + + def __init__(self, trajectory_names: list[str]) -> None: + # We want to parameterise these by paths and potentially a sequence of events + super().__init__() + + self.current_leg = -1 + self.starting_pose = None + self.trajectories: list[SwerveTrajectory] = [] + for trajectory_name in trajectory_names: + try: + self.trajectories.append(choreo.load_swerve_trajectory(trajectory_name)) + if self.starting_pose is None: + self.starting_pose = self.get_starting_pose() + except ValueError: + # If the trajectory is not found, ChoreoLib already prints to DriverStation + pass + + def setup(self) -> None: + # setup path tracking controllers + + # init any other defaults + pass + + def on_enable(self) -> None: + # configure defaults for pose in sim + + # Setup starting position in the simulator + starting_pose = self.get_starting_pose() + if RobotBase.isSimulation() and starting_pose is not None: + self.chassis.set_pose(starting_pose) + # Reset the counter for which leg we are executing + self.current_leg = -1 + + super().on_enable() + + def get_starting_pose(self) -> Pose2d | None: + return self.trajectories[0].get_initial_pose(game.is_red()) + + def _get_full_path_poses(self) -> list[Pose2d]: + """Get a list of poses for the full path for display.""" + return [ + sample.get_pose() + for trajectory in self.trajectories + for sample in trajectory.get_samples() + ] + + def display_trajectory(self) -> None: + self.field.getObject("trajectory").setPoses(self._get_full_path_poses()) + + def on_disable(self) -> None: + super().on_disable() + self.field.getObject("trajectory").setPoses([]) + + @state(first=True) + def initialising(self) -> None: + # Add any tasks that need doing first + self.chassis.do_smooth = False + self.chassis.heading_controller.setPID(Kp=1.0, Ki=0.0, Kd=0.0) + self.next_state("tracking_trajectory") + + @state + def tracking_trajectory(self, initial_call, state_tm) -> None: + if initial_call: + self.current_leg += 1 + + if self.current_leg == len(self.trajectories): + self.done() + return + + # get next leg on entry + current_pose = self.chassis.get_pose() + final_pose = self.trajectories[self.current_leg].get_final_pose(game.is_red()) + if final_pose is None: + self.done() + return + + distance = current_pose.translation().distance(final_pose.translation()) + angle_error = (final_pose.rotation() - current_pose.rotation()).radians() + velocity = self.chassis.get_velocity() + speed = math.sqrt(math.pow(velocity.vx, 2.0) + math.pow(velocity.vy, 2.0)) + + if ( + distance < self.DISTANCE_TOLERANCE + and math.isclose(angle_error, 0.0, abs_tol=self.ANGLE_TOLERANCE) + and math.isclose(speed, 0.0, abs_tol=self.TRANSLATIONAL_SPEED_TOLERANCE) + and math.isclose( + velocity.omega, 0.0, abs_tol=self.ROTATIONAL_SPEED_TOLERANCE + ) + and state_tm > self.trajectories[self.current_leg].get_total_time() / 2.0 + ): + self.done() + return + + sample = self.trajectories[self.current_leg].sample_at(state_tm, game.is_red()) + if sample is not None: + self.follow_trajectory(sample) + + def follow_trajectory(self, sample: SwerveSample): + # track path + + pose = self.chassis.get_pose() + + # Generate the next speeds for the robot + speeds = ChassisSpeeds( + sample.vx + x_controller.calculate(pose.X(), sample.x), + sample.vy + y_controller.calculate(pose.Y(), sample.y), + sample.omega + + self.chassis.heading_controller.calculate( + pose.rotation().radians(), sample.heading + ), + ) + + # Apply the generated speeds + self.chassis.drive_field(speeds.vx, speeds.vy, speeds.omega) diff --git a/autonomous/multi_algae_auto.py b/autonomous/multi_algae_auto.py index 27c83a90..df06386d 100644 --- a/autonomous/multi_algae_auto.py +++ b/autonomous/multi_algae_auto.py @@ -1,4 +1,4 @@ -from autonomous.auto_base import AutoBase +from autonomous.auto_base import AutoBase, AutoBaseNoBalls class CentreAuto(AutoBase): @@ -59,3 +59,47 @@ def __init__(self): "AlgaeKLToShootKL", ] ) + + +class LineRotateTest(AutoBaseNoBalls): + MODE_NAME = "TEST LINE rotation" + + def __init__(self) -> None: + super().__init__( + [ + "LineRotateTest", + ] + ) + + +class LineRotateJiggleReductionTest(AutoBaseNoBalls): + MODE_NAME = "TEST JIGGLE REDUCTION LINE rotation" + + def __init__(self) -> None: + super().__init__( + [ + "LineLessJiggleTest", + ] + ) + + +class CurveRotateTest(AutoBaseNoBalls): + MODE_NAME = "TEST CURVE rotation" + + def __init__(self) -> None: + super().__init__( + [ + "CurveRotateTest", + ] + ) + + +class CurveRotateJiggleReductionTest(AutoBaseNoBalls): + MODE_NAME = "TEST JIGGLE REDUCTION CURVE rotation" + + def __init__(self) -> None: + super().__init__( + [ + "CurveLessJiggleTest", + ] + ) diff --git a/deploy/choreo/CurveLessJiggleTest.traj b/deploy/choreo/CurveLessJiggleTest.traj new file mode 100644 index 00000000..79f00b30 --- /dev/null +++ b/deploy/choreo/CurveLessJiggleTest.traj @@ -0,0 +1,398 @@ +{ + "name":"CurveLessJiggleTest", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.5, "y":4.0, "heading":0.0, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.84660005569458, "y":4.7060933113098145, "heading":0.0, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":9.639573097229004, "y":3.2634711265563965, "heading":0.0, "intervals":253, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":10.0, "y":4.0, "heading":3.141592653589793, "intervals":51, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":9.639573097229004, "y":3.2634711265563965, "heading":0.0, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":7.84660005569458, "y":4.7060933113098145, "heading":0.0, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":7.5, "y":4.0, "heading":0.0, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":1.3}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":3.0}}, "enabled":true}, + {"from":"first", "to":2, "data":{"type":"MaxAngularVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":3, "to":5, "data":{"type":"MaxAngularVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":5, "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":0.5}}, "enabled":true}, + {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":0.5}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.84660005569458 m", "val":7.84660005569458}, "y":{"exp":"4.7060933113098145 m", "val":4.7060933113098145}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"9.639573097229004 m", "val":9.639573097229004}, "y":{"exp":"3.2634711265563965 m", "val":3.2634711265563965}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":253, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x + 2.5 m", "val":10.0}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":51, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"9.639573097229004 m", "val":9.639573097229004}, "y":{"exp":"3.2634711265563965 m", "val":3.2634711265563965}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"7.84660005569458 m", "val":7.84660005569458}, "y":{"exp":"4.7060933113098145 m", "val":4.7060933113098145}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"MaxVelocity", "val":1.3}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":{"exp":"MaxAcceleration", "val":3.0}}}, "enabled":true}, + {"from":"first", "to":2, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"3 rad / s", "val":3.0}}}, "enabled":true}, + {"from":3, "to":5, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"3 rad / s", "val":3.0}}}, "enabled":true}, + {"from":5, "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0.5 rad / s", "val":0.5}}}, "enabled":true}, + {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0.5 rad / s", "val":0.5}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.89269,2.87675,3.79672,4.71534,6.69917,7.59302], + "samples":[ + {"t":0.0, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-0.05912, "ay":2.99733, "alpha":6.67408, "fx":[-20.13633,-22.48237,21.06678,18.59606], "fy":[55.65798,19.48662,19.13202,55.59007]}, + {"t":0.02976, "x":7.49997, "y":4.00133, "heading":0.0, "vx":-0.00176, "vy":0.08919, "omega":0.1986, "ax":-0.03879, "ay":2.99863, "alpha":5.51607, "fx":[-16.70266,-18.28013,17.3835,15.65981], "fy":[52.52933,22.57021,22.39238,52.43967]}, + {"t":0.05951, "x":7.4999, "y":4.00531, "heading":0.00591, "vx":-0.00291, "vy":0.17842, "omega":0.36273, "ax":-0.01526, "ay":2.99876, "alpha":4.52837, "fx":[-13.74838,-14.59932,14.46746,13.1174], "fy":[49.75621,25.21668,25.16539,49.79954]}, + {"t":0.08927, "x":7.49981, "y":4.01195, "heading":0.0167, "vx":-0.00337, "vy":0.26765, "omega":0.49748, "ax":0.01227, "ay":2.99867, "alpha":3.69363, "fx":[-11.15101,-11.39829,12.18008,10.98255], "fy":[47.3715,27.4192,27.54219,47.60051]}, + {"t":0.11902, "x":7.49972, "y":4.02124, "heading":0.03151, "vx":-0.003, "vy":0.35688, "omega":0.60739, "ax":0.04488, "ay":2.99824, "alpha":2.99295, "fx":[-8.83547,-8.61777,10.42352,9.2737], "fy":[45.34441,29.2708,29.54093,45.75569]}, + {"t":0.14878, "x":7.49965, "y":4.03318, "heading":0.04958, "vx":-0.00167, "vy":0.44609, "omega":0.69645, "ax":0.08412, "ay":2.99725, "alpha":2.43285, "fx":[-6.72325,-6.19049,9.13062,7.9892], "fy":[44.00833,30.68383,31.04859,44.1216]}, + {"t":0.17854, "x":7.49963, "y":4.04778, "heading":0.0703, "vx":0.00084, "vy":0.53528, "omega":0.76884, "ax":0.13221, "ay":2.99533, "alpha":1.97465, "fx":[-4.76392,-4.00759,8.27301,7.10913], "fy":[42.50239,31.84567,32.24642,43.17217]}, + {"t":0.20829, "x":7.49972, "y":4.06504, "heading":0.09318, "vx":0.00477, "vy":0.62441, "omega":0.8276, "ax":0.19247, "ay":2.99184, "alpha":1.58244, "fx":[-2.87648,-1.99245,7.81741,6.67507], "fy":[41.34269,32.89596,33.2827,42.07079]}, + {"t":0.23805, "x":7.49994, "y":4.08494, "heading":0.11781, "vx":0.0105, "vy":0.71344, "omega":0.87469, "ax":0.27007, "ay":2.98555, "alpha":1.26303, "fx":[-0.96195,-0.02239,7.79592,6.69185], "fy":[40.36578,33.74025,34.05827,41.1133]}, + {"t":0.26781, "x":7.50038, "y":4.10749, "heading":0.14383, "vx":0.01853, "vy":0.80228, "omega":0.91227, "ax":0.37349, "ay":2.974, "alpha":1.00303, "fx":[1.11501,2.0568,8.27623,7.22622], "fy":[39.49975,34.38616,34.57863,40.23561]}, + {"t":0.29756, "x":7.50109, "y":4.13268, "heading":0.17098, "vx":0.02965, "vy":0.89077, "omega":0.94211, "ax":0.51751, "ay":2.95182, "alpha":0.79559, "fx":[3.56418,4.47315,9.41108,8.4269], "fy":[38.666,34.72584,34.83331,39.36571]}, + {"t":0.32732, "x":7.5022, "y":4.1605, "heading":0.19901, "vx":0.04505, "vy":0.9786, "omega":0.96579, "ax":0.72982, "ay":2.90582, "alpha":0.62407, "fx":[6.75616,7.60435,11.52059,10.6098], "fy":[37.63271,34.72974,34.64682,38.28179]}, + {"t":0.35707, "x":7.50387, "y":4.1909, "heading":0.22775, "vx":0.06676, "vy":1.06507, "omega":0.98436, "ax":1.06608, "ay":2.79869, "alpha":0.4861, "fx":[11.40836,12.17823,15.27516,14.44239], "fy":[35.93952,33.85966,33.60696,36.52855]}, + {"t":0.38683, "x":7.50633, "y":4.22383, "heading":0.25704, "vx":0.09849, "vy":1.14835, "omega":0.99882, "ax":1.63736, "ay":2.50526, "alpha":0.38247, "fx":[18.93061,19.61932,22.03157,21.28653], "fy":[32.04009,30.44544,30.20731,32.56994]}, + {"t":0.41659, "x":7.50998, "y":4.25911, "heading":0.28676, "vx":0.14721, "vy":1.2229, "omega":1.0102, "ax":2.53037, "ay":1.59278, "alpha":0.31213, "fx":[30.43249,31.02642,32.83551,32.22408], "fy":[20.51101,19.01668,19.09036,21.02109]}, + {"t":0.44634, "x":7.51548, "y":4.29621, "heading":0.31682, "vx":0.2225, "vy":1.27029, "omega":1.01949, "ax":2.97472, "ay":-0.29365, "alpha":0.27911, "fx":[36.25489,36.71074,38.11304,37.6573], "fy":[-3.10414,-4.87562,-4.11344,-2.58937]}, + {"t":0.4761, "x":7.52342, "y":4.33388, "heading":0.34716, "vx":0.31102, "vy":1.26155, "omega":1.0278, "ax":2.87883, "ay":-0.81232, "alpha":0.22209, "fx":[35.23934,35.6144,36.73363,36.35418], "fy":[-9.74204,-11.1263,-10.46642,-9.28126]}, + {"t":0.50586, "x":7.53395, "y":4.37106, "heading":0.37774, "vx":0.39668, "vy":1.23738, "omega":1.03441, "ax":2.81648, "ay":-1.0124, "alpha":0.18488, "fx":[34.60382,34.91384,35.81598,35.49025], "fy":[-12.31921,-13.53697,-12.84416,-11.91956]}, + {"t":0.53561, "x":7.547, "y":4.40743, "heading":0.40852, "vx":0.48049, "vy":1.20726, "omega":1.03991, "ax":2.74012, "ay":-1.20701, "alpha":0.15257, "fx":[33.76025,34.01689,34.75597,34.4729], "fy":[-14.82331,-15.84477,-15.20367,-14.47852]}, + {"t":0.56537, "x":7.56251, "y":4.44282, "heading":0.43947, "vx":0.56202, "vy":1.17134, "omega":1.04445, "ax":2.61592, "ay":-1.45876, "alpha":0.12924, "fx":[32.28965,32.50787,33.12486,32.87371], "fy":[-18.01744,-18.90693,-18.29437,-17.71905]}, + {"t":0.59512, "x":7.58039, "y":4.47703, "heading":0.47055, "vx":0.63986, "vy":1.12793, "omega":1.04829, "ax":2.31899, "ay":-1.89689, "alpha":0.11093, "fx":[28.63658,28.83111,29.35557,29.12636], "fy":[-23.53201,-24.30394,-23.73719,-23.27113]}, + {"t":0.62488, "x":7.60046, "y":4.50975, "heading":0.50174, "vx":0.70887, "vy":1.07149, "omega":1.05159, "ax":2.01758, "ay":-2.21569, "alpha":0.10641, "fx":[24.914,25.08138,25.54922,25.33428], "fy":[-27.50702,-28.33944,-27.66339,-27.27479]}, + {"t":0.65464, "x":7.62245, "y":4.54065, "heading":0.53303, "vx":0.7689, "vy":1.00556, "omega":1.05476, "ax":1.77223, "ay":-2.41707, "alpha":0.09609, "fx":[21.87286,22.03884,22.45386,22.24577], "fy":[-30.04923,-30.79741,-30.17214,-29.83481]}, + {"t":0.68439, "x":7.64611, "y":4.5695, "heading":0.56442, "vx":0.82164, "vy":0.93364, "omega":1.05762, "ax":1.57953, "ay":-2.54765, "alpha":0.08889, "fx":[19.47708,19.64932,20.02921,19.82088], "fy":[-31.70353,-32.37914,-31.80276,-31.49682]}, + {"t":0.71415, "x":7.67126, "y":4.59616, "heading":0.59589, "vx":0.86864, "vy":0.85783, "omega":1.06026, "ax":1.42786, "ay":-2.636, "alpha":0.0864, "fx":[17.58375,17.76645,18.12933,17.91346], "fy":[-32.82007,-33.46635,-32.9016,-32.61179]}, + {"t":0.74391, "x":7.69774, "y":4.62051, "heading":0.62744, "vx":0.91113, "vy":0.77939, "omega":1.06283, "ax":1.30688, "ay":-2.69829, "alpha":0.08507, "fx":[16.06254,16.2664,16.62334,16.39163], "fy":[-33.61598,-34.21903,-33.68306,-33.39662]}, + {"t":0.77366, "x":7.72543, "y":4.64251, "heading":0.65906, "vx":0.95002, "vy":0.6991, "omega":1.06537, "ax":1.20882, "ay":-2.74384, "alpha":0.08697, "fx":[14.81724,15.05063,15.41521,15.15806], "fy":[-34.19963,-34.77954,-34.25352,-33.95919]}, + {"t":0.80342, "x":7.75423, "y":4.6621, "heading":0.69076, "vx":0.98599, "vy":0.61745, "omega":1.06795, "ax":1.1281, "ay":-2.77818, "alpha":0.09215, "fx":[13.77712,14.05043,14.43562,14.14161], "fy":[-34.64144,-35.21709,-34.6815,-34.36876]}, + {"t":0.83317, "x":7.78407, "y":4.67924, "heading":0.72254, "vx":1.01955, "vy":0.53479, "omega":1.0707, "ax":1.06067, "ay":-2.80475, "alpha":0.10086, "fx":[12.89014,13.21675,13.63583,13.29085], "fy":[-34.98593,-35.57447,-35.00958,-34.66765]}, + {"t":0.86293, "x":7.81488, "y":4.69391, "heading":0.7544, "vx":1.05111, "vy":0.45133, "omega":1.0737, "ax":1.00363, "ay":-2.82579, "alpha":0.11352, "fx":[12.11738,12.51446,12.98164,12.56794], "fy":[-35.26237,-35.88013,-35.26473,-34.88207]}, + {"t":0.89269, "x":7.8466, "y":4.70609, "heading":0.78635, "vx":1.08098, "vy":0.36724, "omega":1.07708, "ax":0.94765, "ay":-2.84423, "alpha":1.30306, "fx":[6.34708,11.72069,17.33043,11.98409], "fy":[-35.71144,-40.80737,-35.28823,-30.40431]}, + {"t":0.93012, "x":7.88773, "y":4.71785, "heading":0.82667, "vx":1.11645, "vy":0.26077, "omega":1.12586, "ax":0.87419, "ay":-2.8686, "alpha":0.95777, "fx":[6.86687,11.00534,14.98627,10.8511], "fy":[-36.1141,-39.68886,-35.52073,-32.10633]}, + {"t":0.96756, "x":7.93014, "y":4.7256, "heading":0.86882, "vx":1.14918, "vy":0.15338, "omega":1.16171, "ax":0.77939, "ay":-2.89563, "alpha":0.70825, "fx":[6.76636,9.92965,12.72416,9.54916], "fy":[-36.46035,-39.06163,-35.81962,-33.44004]}, + {"t":1.00499, "x":7.9737, "y":4.72931, "heading":0.91231, "vx":1.17836, "vy":0.04498, "omega":1.18822, "ax":0.65364, "ay":-2.92637, "alpha":0.52184, "fx":[6.013,8.40662,10.33652,7.92593], "fy":[-36.8157,-38.73606,-36.20175,-34.5651]}, + {"t":1.04243, "x":8.01827, "y":4.72895, "heading":0.95679, "vx":1.20282, "vy":-0.06457, "omega":1.20776, "ax":0.4802, "ay":-2.9595, "alpha":0.38289, "fx":[4.4589,6.24869,7.55397,5.74827], "fy":[-37.18134,-38.62951,-36.63652,-35.52778]}, + {"t":1.07986, "x":8.06364, "y":4.72446, "heading":1.002, "vx":1.2208, "vy":-0.17536, "omega":1.22209, "ax":0.2293, "ay":-2.98904, "alpha":0.28139, "fx":[1.78031,3.09967,3.95767,2.62754], "fy":[-37.48675,-38.64053,-37.03153,-36.29317]}, + {"t":1.1173, "x":8.1095, "y":4.7158, "heading":1.04775, "vx":1.22939, "vy":-0.28725, "omega":1.23263, "ax":-0.15309, "ay":-2.99335, "alpha":0.20605, "fx":[-2.66351,-1.70284,-1.16395,-2.12406], "fy":[-37.4816,-38.42906,-37.11978,-36.63723]}, + {"t":1.15473, "x":8.15541, "y":4.70295, "heading":1.09389, "vx":1.22365, "vy":-0.39931, "omega":1.24034, "ax":-0.75035, "ay":-2.90099, "alpha":0.15064, "fx":[-9.88623,-9.19418,-8.88108,-9.55578], "fy":[-36.27667,-37.07925,-36.00084,-35.69269]}, + {"t":1.19217, "x":8.2007, "y":4.68597, "heading":1.14033, "vx":1.19557, "vy":-0.50791, "omega":1.24598, "ax":-1.27649, "ay":-2.70975, "alpha":0.11284, "fx":[-16.2917,-15.79745,-15.6387,-16.09646], "fy":[-33.8356,-34.57805,-33.63114,-33.44259]}, + {"t":1.2296, "x":8.24456, "y":4.66505, "heading":1.18697, "vx":1.14778, "vy":-0.60935, "omega":1.2502, "ax":-1.51514, "ay":-2.58198, "alpha":0.08653, "fx":[-19.15654,-18.81226,-18.7442,-19.04378], "fy":[-32.19604,-32.91187,-32.04922,-31.94193]}, + {"t":1.26704, "x":8.28646, "y":4.64043, "heading":1.23377, "vx":1.09106, "vy":-0.706, "omega":1.25344, "ax":-1.73075, "ay":-2.43933, "alpha":0.0691, "fx":[-21.77156,-21.53652,-21.52081,-21.70859], "fy":[-30.3743,-31.09712,-30.2752,-30.21986]}, + {"t":1.30447, "x":8.32609, "y":4.61229, "heading":1.28069, "vx":1.02627, "vy":-0.79732, "omega":1.25603, "ax":-1.93107, "ay":-2.27738, "alpha":0.05978, "fx":[-24.22296,-24.06317,-24.07805,-24.18938], "fy":[-28.30785,-29.09157,-28.247,-28.22238]}, + {"t":1.34191, "x":8.36316, "y":4.58085, "heading":1.32771, "vx":0.95398, "vy":-0.88257, "omega":1.25827, "ax":-2.11164, "ay":-2.09546, "alpha":0.04293, "fx":[-26.44559,-26.34603,-26.36259,-26.42786], "fy":[-26.05693,-26.68173,-26.02189,-26.01249]}, + {"t":1.37934, "x":8.39739, "y":4.54634, "heading":1.37482, "vx":0.87493, "vy":-0.96102, "omega":1.25987, "ax":-2.25871, "ay":-1.88796, "alpha":0.04619, "fx":[-28.26283,-28.20165,-28.21684,-28.25396], "fy":[-23.40913,-24.20815,-23.3915,-23.38898]}, + {"t":1.41678, "x":8.42856, "y":4.50904, "heading":1.42198, "vx":0.79037, "vy":-1.03169, "omega":1.2616, "ax":-2.28144, "ay":-1.6067, "alpha":0.03069, "fx":[-28.53535,-28.49939,-28.50651,-28.5309], "fy":[-19.94964,-20.50614,-19.93986,-19.93917]}, + {"t":1.45421, "x":8.45655, "y":4.4693, "heading":1.46921, "vx":0.70497, "vy":-1.09184, "omega":1.26275, "ax":-1.01556, "ay":-0.63124, "alpha":0.01002, "fx":[-12.7078,-12.68291,-12.68217,-12.70533], "fy":[-7.85846,-8.00758,-7.84829,-7.84758]}, + {"t":1.49165, "x":8.48223, "y":4.42798, "heading":1.51648, "vx":0.66695, "vy":-1.11547, "omega":1.26313, "ax":-0.21479, "ay":-0.12738, "alpha":0.00082, "fx":[-2.69826,-2.67269,-2.67167,-2.69701], "fy":[-1.61567,-1.55444,-1.59974,-1.59912]}, + {"t":1.52908, "x":8.50705, "y":4.38613, "heading":1.56376, "vx":0.65891, "vy":-1.12024, "omega":1.26316, "ax":0.00659, "ay":0.00388, "alpha":-0.00096, "fx":[0.06894,0.09574,0.09574,0.06895], "fy":[0.01003,0.12442,0.02972,0.0296]}, + {"t":1.56652, "x":8.53172, "y":4.3442, "heading":1.61105, "vx":0.65916, "vy":-1.12009, "omega":1.26312, "ax":0.02665, "ay":0.0157, "alpha":0.00096, "fx":[0.32119,0.34618,0.34498,0.32001], "fy":[0.16751,0.24026,0.18907,0.18801]}, + {"t":1.60395, "x":8.55641, "y":4.30228, "heading":1.65834, "vx":0.66015, "vy":-1.11951, "omega":1.26316, "ax":0.01436, "ay":0.00847, "alpha":0.00138, "fx":[0.16996,0.19103,0.18902,0.16795], "fy":[0.08282,0.13658,0.103,0.10119]}, + {"t":1.64139, "x":8.58114, "y":4.26038, "heading":1.70562, "vx":0.66069, "vy":-1.11919, "omega":1.26321, "ax":0.00085, "ay":0.0005, "alpha":0.00138, "fx":[0.00391,0.01945,0.01722,0.00168], "fy":[-0.01042,0.02508,0.0062,0.00408]}, + {"t":1.67882, "x":8.60587, "y":4.21848, "heading":1.75291, "vx":0.66072, "vy":-1.11917, "omega":1.26326, "ax":-0.00347, "ay":-0.00205, "alpha":0.00071, "fx":[-0.04703,-0.03791,-0.03967,-0.04879], "fy":[-0.03766,-0.0097,-0.0266,-0.0284]}, + {"t":1.71626, "x":8.6306, "y":4.17658, "heading":1.8002, "vx":0.66059, "vy":-1.11925, "omega":1.26329, "ax":-0.00405, "ay":-0.00239, "alpha":-0.00019, "fx":[-0.05149,-0.04934,-0.04987,-0.05202], "fy":[-0.03697,-0.01575,-0.03307,-0.03384]}, + {"t":1.75369, "x":8.65533, "y":4.13468, "heading":1.84749, "vx":0.66044, "vy":-1.11934, "omega":1.26328, "ax":-0.00276, "ay":-0.00163, "alpha":-0.00127, "fx":[-0.03267,-0.03778,-0.03631,-0.03119], "fy":[-0.02212,-0.00673,-0.02678,-0.02574]}, + {"t":1.79113, "x":8.68005, "y":4.09278, "heading":1.89478, "vx":0.66034, "vy":-1.1194, "omega":1.26323, "ax":-0.00147, "ay":-0.00087, "alpha":-0.00247, "fx":[-0.01418,-0.02682,-0.02251,-0.00988], "fy":[-0.00652,0.00182,-0.02116,-0.01743]}, + {"t":1.82856, "x":8.70477, "y":4.05087, "heading":1.94207, "vx":0.66028, "vy":-1.11943, "omega":1.26314, "ax":-0.00053, "ay":-0.00031, "alpha":-0.00381, "fx":[-0.00044,-0.02089,-0.01282,0.00764], "fy":[0.00732,0.00733,-0.01885,-0.01143]}, + {"t":1.866, "x":8.72949, "y":4.00897, "heading":1.98936, "vx":0.66026, "vy":-1.11944, "omega":1.263, "ax":0.00009, "ay":0.00005, "alpha":-0.00536, "fx":[0.00907,-0.01973,-0.00677,0.02204], "fy":[0.01989,0.01003,-0.01976,-0.00744]}, + {"t":1.90344, "x":8.7542, "y":3.96706, "heading":2.03664, "vx":0.66027, "vy":-1.11944, "omega":1.2628, "ax":0.00069, "ay":0.00041, "alpha":-0.00719, "fx":[0.01803,-0.01996,-0.00067,0.03733], "fy":[0.03361,0.01223,-0.02207,-0.00329]}, + {"t":1.94087, "x":8.77892, "y":3.92516, "heading":2.08391, "vx":0.66029, "vy":-1.11942, "omega":1.26253, "ax":0.00157, "ay":0.00092, "alpha":-0.00944, "fx":[0.03007,-0.01843,0.00913,0.05763], "fy":[0.0511,0.01617,-0.02416,0.00314]}, + {"t":1.97831, "x":8.80364, "y":3.88325, "heading":2.13118, "vx":0.66035, "vy":-1.11939, "omega":1.26217, "ax":0.00276, "ay":0.00163, "alpha":-0.01227, "fx":[0.04575,-0.0152,0.02331,0.08426], "fy":[0.07338,0.02211,-0.02632,0.01232]}, + {"t":2.01574, "x":8.82836, "y":3.84135, "heading":2.17843, "vx":0.66046, "vy":-1.11933, "omega":1.26172, "ax":0.00394, "ay":0.00232, "alpha":-0.01592, "fx":[0.06068,-0.01549,0.03779,0.11396], "fy":[0.09896,0.02735,-0.03202,0.02192]}, + {"t":2.05318, "x":8.85309, "y":3.79945, "heading":2.22566, "vx":0.6606, "vy":-1.11924, "omega":1.26112, "ax":0.00339, "ay":0.002, "alpha":-0.02072, "fx":[0.05323,-0.042,0.03148,0.12671], "fy":[0.11701,0.01763,-0.05473,0.0201]}, + {"t":2.09061, "x":8.87782, "y":3.75755, "heading":2.27287, "vx":0.66073, "vy":-1.11917, "omega":1.26034, "ax":-0.00086, "ay":-0.00051, "alpha":-0.02713, "fx":[-0.00171,-0.1212,-0.01973,0.09976], "fy":[0.11494,-0.02252,-0.11069,-0.00705]}, + {"t":2.12805, "x":8.90256, "y":3.71565, "heading":2.32005, "vx":0.6607, "vy":-1.11919, "omega":1.25933, "ax":-0.01373, "ay":-0.0081, "alpha":-0.03578, "fx":[-0.16661,-0.31726,-0.17667,-0.02603], "fy":[0.06105,-0.13669,-0.23657,-0.09289]}, + {"t":2.16548, "x":8.92728, "y":3.67375, "heading":2.36719, "vx":0.66018, "vy":-1.11949, "omega":1.25799, "ax":-0.02804, "ay":-0.01652, "alpha":-0.04762, "fx":[-0.35285,-0.54361,-0.34807,-0.15733], "fy":[0.01068,-0.26869,-0.3837,-0.1841]}, + {"t":2.20292, "x":8.95197, "y":3.63183, "heading":2.41429, "vx":0.65913, "vy":-1.12011, "omega":1.25621, "ax":-0.01679, "ay":-0.00988, "alpha":-0.06393, "fx":[-0.22522,-0.46749,-0.19459,0.04764], "fy":[0.17128,-0.23573,-0.35358,-0.07573]}, + {"t":2.24035, "x":8.97664, "y":3.58989, "heading":2.46131, "vx":0.65851, "vy":-1.12048, "omega":1.25381, "ax":0.16399, "ay":0.09698, "alpha":-0.08582, "fx":[2.01281,1.70546,2.08693,2.39407], "fy":[1.5909,1.08979,0.89077,1.27753]}, + {"t":2.27779, "x":9.0014, "y":3.54801, "heading":2.50825, "vx":0.66464, "vy":-1.11685, "omega":1.2506, "ax":0.86493, "ay":0.53203, "alpha":-0.11359, "fx":[10.73906,10.35288,10.88481,11.26971], "fy":[7.10526,6.61527,6.17257,6.70831]}, + {"t":2.31522, "x":9.02689, "y":3.50658, "heading":2.55506, "vx":0.69702, "vy":-1.09693, "omega":1.24635, "ax":2.23804, "ay":1.54865, "alpha":-0.14598, "fx":[27.84653,27.37086,28.10872,28.5759], "fy":[19.86058,19.58174,18.62977,19.36026]}, + {"t":2.35266, "x":9.05455, "y":3.4666, "heading":2.60172, "vx":0.7808, "vy":-1.03896, "omega":1.24088, "ax":2.27069, "ay":1.86217, "alpha":-0.18995, "fx":[28.1683,27.59034,28.60856,29.16724], "fy":[23.90561,23.63508,22.28954,23.27819]}, + {"t":2.39009, "x":9.08537, "y":3.42901, "heading":2.64817, "vx":0.86581, "vy":-0.96925, "omega":1.23377, "ax":2.12995, "ay":2.07389, "alpha":-0.2571, "fx":[26.28072,25.57878,26.98361,27.65451], "fy":[26.84203,26.07227,24.71945,26.06068]}, + {"t":2.42753, "x":9.11928, "y":3.39418, "heading":2.69436, "vx":0.94554, "vy":-0.89161, "omega":1.22415, "ax":1.95214, "ay":2.25822, "alpha":-0.34395, "fx":[23.8714,23.01387,24.95723,25.76454], "fy":[29.45199,28.30629,26.66449,28.48831]}, + {"t":2.46496, "x":9.15604, "y":3.36238, "heading":2.74019, "vx":1.01862, "vy":-0.80707, "omega":1.21127, "ax":1.75373, "ay":2.42233, "alpha":-0.46266, "fx":[21.11917,20.08839,22.75582,23.72322], "fy":[31.92891,30.1487,28.28135,30.75774]}, + {"t":2.5024, "x":9.1954, "y":3.33387, "heading":2.78553, "vx":1.08427, "vy":-0.71639, "omega":1.19395, "ax":1.53975, "ay":2.56709, "alpha":-0.6261, "fx":[18.05556,16.83348,20.47287,21.6258], "fy":[34.3303,31.50825,29.58091,32.93521]}, + {"t":2.53983, "x":9.23707, "y":3.30885, "heading":2.83023, "vx":1.14191, "vy":-0.62029, "omega":1.17051, "ax":1.31025, "ay":2.69342, "alpha":-0.84315, "fx":[14.6462,13.18288,18.15399,19.5294], "fy":[36.6248,32.5531,30.47987,35.01301]}, + {"t":2.57727, "x":9.28074, "y":3.28752, "heading":2.87404, "vx":1.19096, "vy":-0.51946, "omega":1.13895, "ax":0.95629, "ay":2.83963, "alpha":-1.13422, "fx":[9.48989,7.70348,14.48127,16.13981], "fy":[39.34213,33.62056,31.4481,37.5708]}, + {"t":2.6147, "x":9.32599, "y":3.27006, "heading":2.91668, "vx":1.22676, "vy":-0.41316, "omega":1.09649, "ax":0.32963, "ay":2.97897, "alpha":-1.51904, "fx":[0.66733,-1.50413,7.67843,9.64], "fy":[42.19653,34.3704,32.04841,40.33315]}, + {"t":2.65214, "x":9.37215, "y":3.25668, "heading":2.95773, "vx":1.2391, "vy":-0.30164, "omega":1.03962, "ax":-0.09969, "ay":2.99608, "alpha":-2.03109, "fx":[-6.04947,-8.63507,3.74349,5.95668], "fy":[43.86164,33.154,30.8038,41.98447]}, + {"t":2.68957, "x":9.41846, "y":3.24749, "heading":2.99665, "vx":1.23537, "vy":-0.18949, "omega":0.96359, "ax":-0.38256, "ay":2.97364, "alpha":-2.68123, "fx":[-11.4327,-14.4064,2.18341,4.52784], "fy":[45.11081,31.0443,28.77816,43.74855]}, + {"t":2.72701, "x":9.46444, "y":3.24248, "heading":3.03272, "vx":1.22105, "vy":-0.07817, "omega":0.86322, "ax":-0.57723, "ay":2.94235, "alpha":-3.52603, "fx":[-16.26286,-19.67331,2.3963,4.67847], "fy":[47.08493,28.22446,26.17744,45.63064]}, + {"t":2.76444, "x":9.50975, "y":3.24161, "heading":3.06503, "vx":1.19944, "vy":0.03198, "omega":0.73122, "ax":-0.71752, "ay":2.91154, "alpha":-4.61515, "fx":[-21.07498,-24.97665,4.13111,6.04468], "fy":[49.49339,24.59646,22.91061,48.57667]}, + {"t":2.80188, "x":9.55414, "y":3.24485, "heading":3.09241, "vx":1.17258, "vy":0.14097, "omega":0.55845, "ax":-0.82268, "ay":2.88377, "alpha":-5.96266, "fx":[-26.16035,-30.68995,7.28845,8.42803], "fy":[52.51364,20.22394,19.04183,52.40888]}, + {"t":2.83931, "x":9.59746, "y":3.25215, "heading":3.11331, "vx":1.14178, "vy":0.24893, "omega":0.33524, "ax":-0.90409, "ay":2.85942, "alpha":-7.58899, "fx":[-31.63379,-37.09852,11.81802,11.70962], "fy":[56.22161,15.11147,14.46692,57.17115]}, + {"t":2.87675, "x":9.63957, "y":3.26347, "heading":3.12586, "vx":1.10794, "vy":0.35597, "omega":0.05114, "ax":-0.94513, "ay":2.83969, "alpha":-1.0941, "fx":[-14.83776,-15.44313,-8.60549,-8.37002], "fy":[38.46026,32.42605,32.5247,38.57333]}, + {"t":2.88732, "x":9.65124, "y":3.26739, "heading":3.1264, "vx":1.09794, "vy":0.386, "omega":0.03957, "ax":-0.96622, "ay":2.83625, "alpha":-0.7387, "fx":[-14.10688,-14.54629,-9.91939,-9.73865], "fy":[37.44705,33.37357,33.45961,37.53205]}, + {"t":2.8979, "x":9.66279, "y":3.27163, "heading":3.12682, "vx":1.08773, "vy":0.41599, "omega":0.03176, "ax":-0.98736, "ay":2.82884, "alpha":-0.50524, "fx":[-13.70432,-14.06235,-10.86383,-10.73754], "fy":[36.72149,33.93888,34.00318,36.77829]}, + {"t":2.90847, "x":9.67424, "y":3.27619, "heading":3.12716, "vx":1.07729, "vy":0.4459, "omega":0.02642, "ax":-1.00976, "ay":2.82079, "alpha":-0.34563, "fx":[-13.53433,-13.82279,-11.60886,-11.5221], "fy":[36.1892,34.28731,34.33597,36.22706]}, + {"t":2.91905, "x":9.68557, "y":3.28106, "heading":3.12744, "vx":1.06661, "vy":0.47573, "omega":0.02277, "ax":-1.03354, "ay":2.81203, "alpha":-0.2371, "fx":[-13.52123,-13.7753,-12.21965,-12.16092], "fy":[35.7839,34.48602,34.52259,35.80893]}, + {"t":2.92962, "x":9.6968, "y":3.28625, "heading":3.12768, "vx":1.05568, "vy":0.50547, "omega":0.02026, "ax":-1.05882, "ay":2.80246, "alpha":-0.16319, "fx":[-13.61995,-13.86674,-12.74661,-12.70766], "fy":[35.46083,34.57832,34.60704,35.47698]}, + {"t":2.9402, "x":9.7079, "y":3.29175, "heading":3.12789, "vx":1.04448, "vy":0.5351, "omega":0.01853, "ax":-1.08572, "ay":2.79199, "alpha":-0.11466, "fx":[-13.79101,-14.09136,-13.21441,-13.18947], "fy":[35.18972,34.5914,34.61889,35.1997]}, + {"t":2.95077, "x":9.71888, "y":3.29757, "heading":3.12809, "vx":1.033, "vy":0.56463, "omega":0.01732, "ax":-1.11442, "ay":2.7805, "alpha":-0.07916, "fx":[-14.0476,-14.3393,-13.67467,-13.65939], "fy":[34.94868,34.54935,34.57261,34.95431]}, + {"t":2.96134, "x":9.72974, "y":3.30369, "heading":3.12827, "vx":1.02122, "vy":0.59403, "omega":0.01648, "ax":-1.14507, "ay":2.76784, "alpha":-0.05587, "fx":[-14.35321,-14.66675,-14.12093,-14.11237], "fy":[34.72326,34.46088,34.48202,34.72583]}, + {"t":2.97192, "x":9.74048, "y":3.31013, "heading":3.12845, "vx":1.00911, "vy":0.6233, "omega":0.01589, "ax":-1.17785, "ay":2.75386, "alpha":-0.03922, "fx":[-14.71184,-15.02997,-14.57716,-14.57328], "fy":[34.5018,34.33463,34.35422,34.5022]}, + {"t":2.98249, "x":9.75108, "y":3.31688, "heading":3.12861, "vx":0.99665, "vy":0.65242, "omega":0.01548, "ax":-1.21298, "ay":2.73835, "alpha":-0.02757, "fx":[-15.11542,-15.43608,-15.04914,-15.04858], "fy":[34.27555,34.17428,34.19344,34.27435]}, + {"t":2.99307, "x":9.76156, "y":3.32393, "heading":3.12878, "vx":0.98383, "vy":0.68137, "omega":0.01519, "ax":-1.25071, "ay":2.7211, "alpha":-0.01821, "fx":[-15.56764,-15.86649,-15.54978,-15.5516], "fy":[34.03657,33.98384,34.00053,34.03417]}, + {"t":3.00364, "x":9.77189, "y":3.33128, "heading":3.12894, "vx":0.9706, "vy":0.71015, "omega":0.01499, "ax":-1.29129, "ay":2.70184, "alpha":-0.01293, "fx":[-16.05059,-16.37119,-16.06943,-16.07309], "fy":[33.77892,33.76016,33.77729,33.77551]}, + {"t":3.01422, "x":9.78208, "y":3.33895, "heading":3.1291, "vx":0.95695, "vy":0.73872, "omega":0.01486, "ax":-1.335, "ay":2.68024, "alpha":-0.0086, "fx":[-16.57821,-16.9133,-16.62653,-16.63174], "fy":[33.49583,33.50354,33.52124,33.49149]}, + {"t":3.02479, "x":9.79212, "y":3.34691, "heading":3.12925, "vx":0.94283, "vy":0.76706, "omega":0.01477, "ax":-1.38219, "ay":2.65592, "alpha":-0.00643, "fx":[-17.14206,-17.52726,-17.21665,-17.22332], "fy":[33.18052,33.21106,33.22924,33.17523]}, + {"t":3.03537, "x":9.80202, "y":3.35517, "heading":3.12941, "vx":0.92821, "vy":0.79515, "omega":0.0147, "ax":-1.4332, "ay":2.62842, "alpha":-0.00804, "fx":[-17.73481,-18.24638,-17.83535,-17.8436], "fy":[32.82805,32.87217,32.89913,32.82168]}, + {"t":3.04594, "x":9.81175, "y":3.36372, "heading":3.12957, "vx":0.91306, "vy":0.82294, "omega":0.01461, "ax":-1.48844, "ay":2.59719, "alpha":-0.00557, "fx":[-18.4132,-18.93557,-18.5319,-18.54126], "fy":[32.43038,32.4888,32.51693,32.42318]}, + {"t":3.05651, "x":9.82132, "y":3.37257, "heading":3.12972, "vx":0.89732, "vy":0.8504, "omega":0.01455, "ax":-1.5483, "ay":2.56156, "alpha":-0.00553, "fx":[-19.14396,-19.71087,-19.27513,-19.28524], "fy":[31.98026,32.04792,32.07724,31.97241]}, + {"t":3.06709, "x":9.83073, "y":3.3817, "heading":3.12987, "vx":0.88095, "vy":0.87749, "omega":0.0145, "ax":-1.61327, "ay":2.52071, "alpha":0.00006, "fx":[-19.97543,-20.44841,-20.11446,-20.1251], "fy":[31.46534,31.54449,31.56879,31.45698]}, + {"t":3.07766, "x":9.83995, "y":3.39112, "heading":3.13003, "vx":0.86389, "vy":0.90415, "omega":0.0145, "ax":-1.68375, "ay":2.4737, "alpha":-0.00033, "fx":[-20.84163,-21.35584,-20.98954,-21.00069], "fy":[30.87439,30.95965,30.98544,30.86553]}, + {"t":3.08824, "x":9.84899, "y":3.40082, "heading":3.13018, "vx":0.84608, "vy":0.9303, "omega":0.01449, "ax":-1.76017, "ay":2.41938, "alpha":-0.0013, "fx":[-21.77716,-22.34961,-21.93505,-21.94674], "fy":[30.19164,30.28323,30.3117,30.18228]}, + {"t":3.09881, "x":9.85784, "y":3.4108, "heading":3.13033, "vx":0.82747, "vy":0.95589, "omega":0.01448, "ax":-1.84283, "ay":2.35641, "alpha":-0.00221, "fx":[-22.78965,-23.42334,-22.95817,-22.97042], "fy":[29.4001,29.50012,29.5301,29.39021]}, + {"t":3.10939, "x":9.86649, "y":3.42104, "heading":3.13049, "vx":0.80798, "vy":0.9808, "omega":0.01446, "ax":-1.93188, "ay":2.28328, "alpha":-0.00471, "fx":[-23.87266,-24.60336,-24.05258,-24.06539], "fy":[28.4821,28.58722,28.62306,28.47169]}, + {"t":3.11996, "x":9.87492, "y":3.43154, "heading":3.13064, "vx":0.78756, "vy":1.00495, "omega":0.01441, "ax":-2.02705, "ay":2.19844, "alpha":-0.00171, "fx":[-25.06488,-25.76543,-25.25434,-25.26762], "fy":[27.41701,27.53166,27.56734,27.40615]}, + {"t":3.13053, "x":9.88314, "y":3.44228, "heading":3.13079, "vx":0.76612, "vy":1.0282, "omega":0.01439, "ax":-2.12751, "ay":2.10047, "alpha":-0.00176, "fx":[-26.30616,-27.04558,-26.50506,-26.51874], "fy":[26.18789,26.31149,26.34759,26.17663]}, + {"t":3.14111, "x":9.89112, "y":3.45327, "heading":3.13094, "vx":0.74362, "vy":1.05041, "omega":0.01437, "ax":-2.23131, "ay":1.98883, "alpha":-0.00613, "fx":[-27.5675,-28.43203,-27.77588,-27.78991], "fy":[24.79113,24.91059,24.9603,24.77954]}, + {"t":3.15168, "x":9.89886, "y":3.46449, "heading":3.1311, "vx":0.72003, "vy":1.07144, "omega":0.0143, "ax":-2.33489, "ay":1.86495, "alpha":-0.00881, "fx":[-28.84273,-29.78027,-29.05373,-29.06769], "fy":[23.2411,23.36428,23.41273,23.22946]}, + {"t":3.16226, "x":9.90634, "y":3.47593, "heading":3.13125, "vx":0.69534, "vy":1.09116, "omega":0.01421, "ax":-2.43249, "ay":1.73435, "alpha":-0.01447, "fx":[-30.03592,-31.08803,-30.24358,-30.25708], "fy":[21.61071,21.72963,21.77805,21.59928]}, + {"t":3.17283, "x":9.91356, "y":3.48756, "heading":3.1314, "vx":0.66962, "vy":1.1095, "omega":0.01406, "ax":-2.51677, "ay":1.60804, "alpha":0.00052, "fx":[-31.18499,-31.8779,-31.38139,-31.39423], "fy":[20.02943,20.16865,20.18537,20.01845]}, + {"t":3.18341, "x":9.9205, "y":3.49939, "heading":3.13155, "vx":0.643, "vy":1.1265, "omega":0.01406, "ax":-2.58264, "ay":1.49814, "alpha":0.00557, "fx":[-32.03692,-32.61272,-32.23489,-32.24745], "fy":[18.65657,18.79121,18.81332,18.64579]}, + {"t":3.19398, "x":9.92715, "y":3.51138, "heading":3.1317, "vx":0.61569, "vy":1.14234, "omega":0.01412, "ax":-2.6318, "ay":1.40788, "alpha":0.00639, "fx":[-32.6393,-33.2403,-32.84882,-32.86149], "fy":[17.52299,17.66714,17.69151,17.51227]}, + {"t":3.20456, "x":9.93352, "y":3.52354, "heading":3.13184, "vx":0.58786, "vy":1.15723, "omega":0.01419, "ax":-2.67029, "ay":1.33098, "alpha":0.01312, "fx":[-33.1283,-33.65727,-33.35789,-33.37096], "fy":[16.55108,16.71658,16.74089,16.54032]}, + {"t":3.21513, "x":9.93959, "y":3.53585, "heading":3.13199, "vx":0.55963, "vy":1.17131, "omega":0.01433, "ax":-2.70303, "ay":1.26031, "alpha":0.01009, "fx":[-33.4709,-34.20184,-33.73237,-33.74618], "fy":[15.65049,15.85078,15.87453,15.63961]}, + {"t":3.2257, "x":9.94535, "y":3.54831, "heading":3.13215, "vx":0.53104, "vy":1.18463, "omega":0.01444, "ax":-2.73248, "ay":1.19176, "alpha":-0.01924, "fx":[-33.60844,-35.1671,-33.91688,-33.93167], "fy":[14.77882,14.98913,15.05215,14.76785]}, + {"t":3.23628, "x":9.95081, "y":3.5609, "heading":3.1323, "vx":0.50215, "vy":1.19724, "omega":0.01423, "ax":-2.75962, "ay":1.12358, "alpha":-0.00963, "fx":[-33.9528,-35.42697,-34.29289,-34.3081], "fy":[13.90806,14.15887,14.21478,13.8973]}, + {"t":3.24685, "x":9.95597, "y":3.57362, "heading":3.13245, "vx":0.47297, "vy":1.20912, "omega":0.01413, "ax":-2.78474, "ay":1.05514, "alpha":-0.00025, "fx":[-34.2837,-35.64181,-34.64816,-34.66338], "fy":[13.03934,13.31775,13.37078,13.02908]}, + {"t":3.25743, "x":9.96082, "y":3.58647, "heading":3.1326, "vx":0.44352, "vy":1.22027, "omega":0.01413, "ax":-2.80793, "ay":0.98627, "alpha":-0.00327, "fx":[-34.53869,-36.01484,-34.91423,-34.92877], "fy":[12.17121,12.46671,12.51381,12.16188]}, + {"t":3.268, "x":9.96535, "y":3.59943, "heading":3.13275, "vx":0.41383, "vy":1.2307, "omega":0.01409, "ax":-2.82918, "ay":0.91696, "alpha":-0.01067, "fx":[-34.75959,-36.414,-35.13611,-35.14951], "fy":[11.30238,11.60488,11.64628,11.29427]}, + {"t":3.27858, "x":9.96957, "y":3.61249, "heading":3.1329, "vx":0.38391, "vy":1.2404, "omega":0.01398, "ax":-2.84848, "ay":0.8472, "alpha":0.03303, "fx":[-35.26652,-35.88003,-35.63286,-35.64483], "fy":[10.43333,10.73296,10.76738,10.42655]}, + {"t":3.28915, "x":9.97347, "y":3.62566, "heading":3.13304, "vx":0.35379, "vy":1.24936, "omega":0.01433, "ax":-2.8658, "ay":0.77707, "alpha":0.02338, "fx":[-35.44075,-36.24336,-35.79771,-35.80816], "fy":[9.55918,9.85576,9.88472,9.55386]}, + {"t":3.29973, "x":9.97705, "y":3.63891, "heading":3.1332, "vx":0.32349, "vy":1.25758, "omega":0.01458, "ax":-2.88114, "ay":0.70644, "alpha":0.01482, "fx":[-35.5997,-36.55829,-35.94506,-35.95387], "fy":[8.67969,8.97154,8.99492,8.67593]}, + {"t":3.3103, "x":9.98031, "y":3.65225, "heading":3.13335, "vx":0.29302, "vy":1.26505, "omega":0.01473, "ax":-2.89473, "ay":0.63417, "alpha":0.0078, "fx":[-35.74748,-36.82187,-36.07999,-36.08698], "fy":[7.78004,8.06627,8.08403,7.77806]}, + {"t":3.32087, "x":9.98324, "y":3.66566, "heading":3.13351, "vx":0.26241, "vy":1.27175, "omega":0.01482, "ax":-2.90839, "ay":0.55007, "alpha":-0.03039, "fx":[-35.71541,-37.62829,-36.03555,-36.04041], "fy":[6.73135,7.0148,7.0258,6.73156]}, + {"t":3.33145, "x":9.98586, "y":3.67914, "heading":3.13366, "vx":0.23166, "vy":1.27757, "omega":0.01449, "ax":-2.93351, "ay":0.36605, "alpha":-0.03162, "fx":[-36.04531,-37.92967,-36.34915,-36.35135], "fy":[4.43523,4.71369,4.71527,4.43823]}, + {"t":3.34202, "x":9.98814, "y":3.69267, "heading":3.13382, "vx":0.20064, "vy":1.28144, "omega":0.01416, "ax":-2.94115, "ay":-0.27071, "alpha":-0.03206, "fx":[-36.1643,-37.99431,-36.45003,-36.44905], "fy":[-3.51953,-3.24612,-3.2569,-3.51312]}, + {"t":3.3526, "x":9.9901, "y":3.7062, "heading":3.13397, "vx":0.16953, "vy":1.27858, "omega":0.01382, "ax":-2.70021, "ay":-1.20228, "alpha":-0.02909, "fx":[-33.2016,-34.88047,-33.46613,-33.46229], "fy":[-15.15604,-14.89458,-14.91669,-15.14665]}, + {"t":3.36317, "x":9.99174, "y":3.71966, "heading":3.13411, "vx":0.14098, "vy":1.26586, "omega":0.01351, "ax":-2.2489, "ay":-1.92758, "alpha":-0.0221, "fx":[-27.64083,-29.04995,-27.87962,-27.87439], "fy":[-24.2087,-23.97337,-23.99894,-24.19821]}, + {"t":3.37375, "x":9.99311, "y":3.73294, "heading":3.13426, "vx":0.1172, "vy":1.24548, "omega":0.01328, "ax":-1.80327, "ay":-2.35798, "alpha":-0.01317, "fx":[-22.16799,-23.24643,-22.37702,-22.37195], "fy":[-29.5715,-29.37132,-29.39418,-29.56188]}, + {"t":3.38432, "x":9.99424, "y":3.74597, "heading":3.1344, "vx":0.09813, "vy":1.22055, "omega":0.01314, "ax":-1.44699, "ay":-2.59804, "alpha":-0.00123, "fx":[-17.83181,-18.50509,-18.00831,-18.00422], "fy":[-32.55463,-32.39082,-32.40985,-32.54684]}, + {"t":3.3949, "x":9.9952, "y":3.75874, "heading":3.13453, "vx":0.08283, "vy":1.19307, "omega":0.01313, "ax":-1.17631, "ay":-2.73573, "alpha":0.01095, "fx":[-14.56953,-14.82663,-14.71128,-14.7083], "fy":[-34.25775,-34.13174,-34.14522,-34.25194]}, + {"t":3.40547, "x":9.99601, "y":3.7712, "heading":3.13467, "vx":0.07039, "vy":1.16414, "omega":0.01324, "ax":-0.97306, "ay":-2.81774, "alpha":-0.00011, "fx":[-12.01438,-12.39699,-12.12174,-12.11976], "fy":[-35.26629,-35.17505,-35.18357,-35.26228]}, + {"t":3.41604, "x":9.9967, "y":3.78335, "heading":3.13481, "vx":0.0601, "vy":1.13435, "omega":0.01324, "ax":-0.81667, "ay":-2.86948, "alpha":-0.00534, "fx":[-10.07966,-10.4515,-10.15188,-10.1507], "fy":[-35.89659,-35.83993,-35.84351,-35.8941]}, + {"t":3.42662, "x":9.99729, "y":3.79519, "heading":3.13495, "vx":0.05147, "vy":1.104, "omega":0.01319, "ax":-0.69407, "ay":-2.90353, "alpha":0.00794, "fx":[-8.67441,-8.60794,-8.71092,-8.71034], "fy":[-36.30597,-36.28356,-36.28223,-36.30472]}, + {"t":3.43719, "x":9.9978, "y":3.8067, "heading":3.13509, "vx":0.04413, "vy":1.0733, "omega":0.01327, "ax":-0.59566, "ay":-2.92686, "alpha":0.01211, "fx":[-7.51115,-7.23756,-7.51718,-7.51705], "fy":[-36.58439,-36.59034,-36.58433,-36.5841]}, + {"t":3.44777, "x":9.99823, "y":3.81788, "heading":3.13523, "vx":0.03783, "vy":1.04235, "omega":0.0134, "ax":-0.5156, "ay":-2.94329, "alpha":0.01848, "fx":[-6.56934,-6.09253,-6.55902,-6.55907], "fy":[-36.78344,-36.80343,-36.79405,-36.78362]}, + {"t":3.45834, "x":9.9986, "y":3.82874, "heading":3.13537, "vx":0.03238, "vy":1.01123, "omega":0.01359, "ax":-0.44886, "ay":-2.95526, "alpha":0.002, "fx":[-5.63037,-5.5653,-5.62368,-5.62368], "fy":[-36.93924,-36.94165,-36.94258,-36.93935]}, + {"t":3.46892, "x":9.99892, "y":3.83927, "heading":3.13552, "vx":0.02763, "vy":0.97998, "omega":0.01361, "ax":-0.39267, "ay":-2.96413, "alpha":0.00364, "fx":[-4.93236,-4.84488,-4.92804,-4.92802], "fy":[-37.05287,-37.05012,-37.05059,-37.05295]}, + {"t":3.47949, "x":9.99919, "y":3.84947, "heading":3.13566, "vx":0.02348, "vy":0.94863, "omega":0.01365, "ax":-0.34475, "ay":-2.97084, "alpha":0.00323, "fx":[-4.32737,-4.26074,-4.32464,-4.32461], "fy":[-37.13881,-37.13172,-37.13254,-37.13887]}, + {"t":3.49007, "x":9.99942, "y":3.85933, "heading":3.13581, "vx":0.01983, "vy":0.91722, "omega":0.01369, "ax":-0.30343, "ay":-2.97599, "alpha":0.00433, "fx":[-3.81734,-3.7263,-3.81406,-3.81403], "fy":[-37.20376,-37.19581,-37.19617,-37.20382]}, + {"t":3.50064, "x":9.99961, "y":3.86886, "heading":3.13595, "vx":0.01662, "vy":0.88575, "omega":0.01373, "ax":-0.26747, "ay":-2.98, "alpha":0.00497, "fx":[-3.37366,-3.26294,-3.36852,-3.36848], "fy":[-37.2536,-37.24645,-37.24647,-37.25368]}, + {"t":3.51121, "x":9.99977, "y":3.87806, "heading":3.1361, "vx":0.0138, "vy":0.85424, "omega":0.01379, "ax":-0.2359, "ay":-2.98317, "alpha":0.00527, "fx":[-2.98404,-2.85825,-2.97638,-2.97633], "fy":[-37.29232,-37.28687,-37.28665,-37.29242]}, + {"t":3.52179, "x":9.9999, "y":3.88693, "heading":3.13624, "vx":0.0113, "vy":0.82269, "omega":0.01384, "ax":-0.20801, "ay":-2.98568, "alpha":0.00568, "fx":[-2.64146,-2.49698,-2.63115,-2.6311], "fy":[-37.32275,-37.31933,-37.31894,-37.32288]}, + {"t":3.53236, "x":10.00001, "y":3.89546, "heading":3.13639, "vx":0.0091, "vy":0.79112, "omega":0.0139, "ax":-0.18313, "ay":-2.9877, "alpha":0.00582, "fx":[-2.3343,-2.17874,-2.32173,-2.32167], "fy":[-37.34713,-37.34552,-37.34502,-37.34728]}, + {"t":3.54294, "x":10.0001, "y":3.90366, "heading":3.13654, "vx":0.00716, "vy":0.75953, "omega":0.01396, "ax":-0.16083, "ay":-2.98933, "alpha":0.00592, "fx":[-2.05822,-1.89495,-2.04414,-2.04409], "fy":[-37.36695,-37.36656,-37.366,-37.36711]}, + {"t":3.55351, "x":10.00016, "y":3.91153, "heading":3.13668, "vx":0.00546, "vy":0.72792, "omega":0.01403, "ax":-0.14073, "ay":-2.99066, "alpha":0.00605, "fx":[-1.80842,-1.64053,-1.79385,-1.79381], "fy":[-37.38341,-37.38336,-37.38277,-37.38356]}, + {"t":3.56409, "x":10.00021, "y":3.91906, "heading":3.13683, "vx":0.00398, "vy":0.69629, "omega":0.01409, "ax":-0.12253, "ay":-2.99175, "alpha":0.00626, "fx":[-1.58101,-1.41119,-1.56723,-1.56719], "fy":[-37.39738,-37.39657,-37.39597,-37.39753]}, + {"t":3.57466, "x":10.00025, "y":3.92625, "heading":3.13698, "vx":0.00268, "vy":0.66466, "omega":0.01416, "ax":-0.10597, "ay":-2.99264, "alpha":0.00663, "fx":[-1.37285,-1.20323,-1.36134,-1.36131], "fy":[-37.4096,-37.40668,-37.40608,-37.40972]}, + {"t":3.58523, "x":10.00027, "y":3.93311, "heading":3.13713, "vx":0.00156, "vy":0.63301, "omega":0.01423, "ax":-0.09085, "ay":-2.99338, "alpha":0.00722, "fx":[-1.18133,-1.01338,-1.17384,-1.17382], "fy":[-37.42065,-37.41404,-37.41342,-37.42073]}, + {"t":3.59581, "x":10.00028, "y":3.93964, "heading":3.13728, "vx":0.0006, "vy":0.60136, "omega":0.0143, "ax":-0.07697, "ay":-2.99398, "alpha":0.005, "fx":[-0.98603,-0.89322,-0.98473,-0.98473], "fy":[-37.43117,-37.41847,-37.41835,-37.4312]}, + {"t":3.60638, "x":10.00029, "y":3.94583, "heading":3.13743, "vx":-0.00022, "vy":0.5697, "omega":0.01436, "ax":-0.06421, "ay":-2.99449, "alpha":0.00605, "fx":[-0.82464,-0.72808,-0.8288,-0.82881], "fy":[-37.43984,-37.42243,-37.4222,-37.43983]}, + {"t":3.61696, "x":10.00028, "y":3.95169, "heading":3.13758, "vx":-0.00089, "vy":0.53803, "omega":0.01442, "ax":-0.05242, "ay":-2.9949, "alpha":0.00992, "fx":[-0.69179,-0.52597,-0.70156,-0.70159], "fy":[-37.44731,-37.42562,-37.42484,-37.44727]}, + {"t":3.62753, "x":10.00027, "y":3.95721, "heading":3.13774, "vx":-0.00145, "vy":0.50636, "omega":0.01452, "ax":-0.0415, "ay":-2.99524, "alpha":0.01186, "fx":[-0.5526,-0.37817,-0.57212,-0.57216], "fy":[-37.45586,-37.42574,-37.42483,-37.45576]}, + {"t":3.63811, "x":10.00025, "y":3.9624, "heading":3.13789, "vx":-0.00189, "vy":0.47469, "omega":0.01465, "ax":-0.03136, "ay":-2.99553, "alpha":0.01468, "fx":[-0.41984,-0.23844,-0.45489,-0.45493], "fy":[-37.46633,-37.42247,-37.42141,-37.46613]}, + {"t":3.64868, "x":10.00023, "y":3.96725, "heading":3.13805, "vx":-0.00222, "vy":0.44302, "omega":0.0148, "ax":-0.02192, "ay":-2.99576, "alpha":0.01883, "fx":[-0.2918,-0.10348,-0.3504,-0.35042], "fy":[-37.47988,-37.41492,-37.41366,-37.47951]}, + {"t":3.65926, "x":10.0002, "y":3.97177, "heading":3.1382, "vx":-0.00245, "vy":0.41134, "omega":0.015, "ax":-0.01311, "ay":-2.99595, "alpha":0.02486, "fx":[-0.16595,0.02936,-0.25948,-0.25945], "fy":[-37.49815,-37.40166,-37.40013,-37.49755]}, + {"t":3.66983, "x":10.00018, "y":3.97595, "heading":3.13836, "vx":-0.00259, "vy":0.37966, "omega":0.01527, "ax":-0.00487, "ay":-2.9961, "alpha":0.03358, "fx":[-0.03912,0.16339,-0.18389,-0.18376], "fy":[-37.5235,-37.38053,-37.37862,-37.52257]}, + {"t":3.6804, "x":10.00015, "y":3.97979, "heading":3.13852, "vx":-0.00264, "vy":0.34797, "omega":0.01562, "ax":0.00286, "ay":-2.99623, "alpha":0.04622, "fx":[0.09294,0.30307,-0.12667,-0.12636], "fy":[-37.55931,-37.34832,-37.3459,-37.55791]}, + {"t":3.69098, "x":10.00012, "y":3.98331, "heading":3.13869, "vx":-0.00261, "vy":0.31629, "omega":0.01611, "ax":0.01012, "ay":-2.99633, "alpha":0.06451, "fx":[0.2361,0.45447,-0.09264,-0.09201], "fy":[-37.61052,-37.30027,-37.29714,-37.60845]}, + {"t":3.70155, "x":10.00009, "y":3.98648, "heading":3.13886, "vx":-0.0025, "vy":0.28461, "omega":0.01679, "ax":0.01695, "ay":-2.9964, "alpha":0.09106, "fx":[0.39865,0.62616,-0.08928,-0.08806], "fy":[-37.68428,-37.22938,-37.22529,-37.68126]}, + {"t":3.71213, "x":10.00007, "y":3.98933, "heading":3.13903, "vx":-0.00232, "vy":0.25292, "omega":0.01776, "ax":0.02339, "ay":-2.99646, "alpha":0.12966, "fx":[0.59257,0.83042,-0.12787,-0.12562], "fy":[-37.79109,-37.12537,-37.11995,-37.78673]}, + {"t":3.7227, "x":10.00005, "y":3.99183, "heading":3.13922, "vx":-0.00208, "vy":0.22124, "omega":0.01913, "ax":0.02947, "ay":-2.9965, "alpha":0.1859, "fx":[0.83522,1.085,-0.22538,-0.22126], "fy":[-37.94632,-36.97306,-36.96581,-37.94007]}, + {"t":3.73328, "x":10.00003, "y":3.994, "heading":3.13942, "vx":-0.00177, "vy":0.18955, "omega":0.02109, "ax":0.03522, "ay":-2.99653, "alpha":0.26696, "fx":[1.15811,1.39752,-0.40098,-0.39344], "fy":[-38.17262,-36.75001,-36.74039,-38.16366]}, + {"t":3.74385, "x":10.00001, "y":3.99584, "heading":3.13965, "vx":-0.00139, "vy":0.15786, "omega":0.02392, "ax":0.04067, "ay":-2.99655, "alpha":0.38781, "fx":[1.57899,1.86024,-0.70987,-0.6957], "fy":[-38.50232,-36.42442,-36.41129,-38.48951]}, + {"t":3.75443, "x":10.0, "y":3.99734, "heading":3.1399, "vx":-0.00096, "vy":0.12618, "omega":0.02802, "ax":0.04584, "ay":-2.99656, "alpha":0.5633, "fx":[2.17159,2.47395,-1.19013,-1.1633], "fy":[-38.98477,-35.94703,-35.92931,-38.96677]}, + {"t":3.765, "x":9.99999, "y":3.99851, "heading":3.1402, "vx":-0.00048, "vy":0.09449, "omega":0.03397, "ax":0.05075, "ay":-2.99656, "alpha":0.82097, "fx":[3.00988,3.34077,-1.93257,-1.88049], "fy":[-39.69229,-35.24596,-35.2223,-39.66724]}, + {"t":3.77557, "x":9.99999, "y":3.99934, "heading":3.14056, "vx":0.00006, "vy":0.0628, "omega":0.04265, "ax":0.05542, "ay":-2.99655, "alpha":1.20013, "fx":[4.21133,4.58618,-3.06507,-2.96127], "fy":[-40.73191,-34.2144,-34.18342,-40.69762]}, + {"t":3.78615, "x":9.99999, "y":3.99984, "heading":3.14101, "vx":0.00064, "vy":0.03112, "omega":0.05534, "ax":0.05987, "ay":-2.99653, "alpha":1.75933, "fx":[5.94757,6.40025,-4.78326,-4.57108], "fy":[-42.26273,-32.69291,-32.65382,-42.21712]}, + {"t":3.79672, "x":10.0, "y":4.0, "heading":3.14159, "vx":0.00128, "vy":-0.00057, "omega":0.07395, "ax":0.05557, "ay":-2.99739, "alpha":6.17859, "fx":[18.7512,20.69447,-19.43152,-17.23567], "fy":[-54.36959,-20.82071,-20.46537,-54.21393]}, + {"t":3.82636, "x":10.00006, "y":3.99867, "heading":-3.1394, "vx":0.00292, "vy":-0.08939, "omega":0.25704, "ax":0.04125, "ay":-2.99859, "alpha":5.09123, "fx":[15.59328,16.80849,-15.96875,-14.37052], "fy":[-51.38714,-23.68774,-23.56179,-51.293]}, + {"t":3.85599, "x":10.00017, "y":3.9947, "heading":-3.13178, "vx":0.00415, "vy":-0.17825, "omega":0.4079, "ax":0.02465, "ay":-2.99869, "alpha":4.16998, "fx":[12.8942,13.45138,-13.20914,-11.90385], "fy":[-48.77623,-26.1322,-26.17188,-48.85405]}, + {"t":3.88562, "x":10.0003, "y":3.9881, "heading":-3.1197, "vx":0.00488, "vy":-0.26711, "omega":0.53147, "ax":0.00522, "ay":-2.99868, "alpha":3.39416, "fx":[10.54336,10.57077,-11.01988,-9.83339], "fy":[-46.54452,-28.17618,-28.39254,-46.82079]}, + {"t":3.91525, "x":10.00045, "y":3.97887, "heading":-3.10395, "vx":0.00503, "vy":-0.35597, "omega":0.63205, "ax":-0.01784, "ay":-2.99851, "alpha":2.74694, "fx":[8.47384,8.10514,-9.30952,-8.16167], "fy":[-44.67062,-29.88386,-30.24596,-45.12502]}, + {"t":3.94489, "x":10.00059, "y":3.96701, "heading":-3.08522, "vx":0.0045, "vy":-0.44482, "omega":0.71345, "ax":-0.04565, "ay":-2.99807, "alpha":2.22976, "fx":[6.61686,5.98667,-8.00993,-6.87595], "fy":[-43.43656,-31.20092,-31.64447,-43.6214]}, + {"t":3.97452, "x":10.0007, "y":3.95251, "heading":-3.06408, "vx":0.00315, "vy":-0.53366, "omega":0.77952, "ax":-0.07981, "ay":-2.99717, "alpha":1.80896, "fx":[4.92685,4.12158,-7.09078,-5.94811], "fy":[-42.06551,-32.28024,-32.75673,-42.75605]}, + {"t":4.00415, "x":10.00076, "y":3.93538, "heading":-3.04098, "vx":0.00079, "vy":-0.62248, "omega":0.83313, "ax":-0.12277, "ay":-2.99549, "alpha":1.44805, "fx":[3.33353,2.43741,-6.50929,-5.40035], "fy":[-41.01964,-33.26951,-33.72901,-41.75635]}, + {"t":4.03379, "x":10.00073, "y":3.91562, "heading":-3.01629, "vx":-0.00285, "vy":-0.71124, "omega":0.87604, "ax":-0.1784, "ay":-2.9924, "alpha":1.15784, "fx":[1.76777,0.84165,-6.29579,-5.23383], "fy":[-40.16916,-34.06645,-34.4671,-40.91713]}, + {"t":4.06342, "x":10.00057, "y":3.89323, "heading":-2.99033, "vx":-0.00814, "vy":-0.79991, "omega":0.91035, "ax":-0.25317, "ay":-2.9866, "alpha":0.917, "fx":[0.09856,-0.81056,-6.47177,-5.4746], "fy":[-39.43138,-34.72647,-35.0133,-40.15904]}, + {"t":4.09305, "x":10.00021, "y":3.86821, "heading":-2.96335, "vx":-0.01564, "vy":-0.88842, "omega":0.93752, "ax":-0.35872, "ay":-2.97521, "alpha":0.72866, "fx":[-1.80641,-2.67365,-7.1934,-6.26271], "fy":[-38.77737,-35.18993,-35.32218,-39.47101]}, + {"t":4.12268, "x":9.99959, "y":3.84058, "heading":-2.93557, "vx":-0.02627, "vy":-0.97658, "omega":0.95911, "ax":-0.51818, "ay":-2.95077, "alpha":0.56722, "fx":[-4.31428,-5.11173,-8.66501,-7.81811], "fy":[-38.04721,-35.40795,-35.40213,-38.68102]}, + {"t":4.15232, "x":9.99859, "y":3.81035, "heading":-2.90715, "vx":-0.04163, "vy":-1.06402, "omega":0.97592, "ax":-0.78339, "ay":-2.89025, "alpha":0.45206, "fx":[-8.01142,-8.74643,-11.5964,-10.81515], "fy":[-37.00216,-35.02221,-34.90335,-37.58468]}, + {"t":4.18195, "x":9.99701, "y":3.77755, "heading":-2.87823, "vx":-0.06484, "vy":-1.14966, "omega":0.98932, "ax":-1.28793, "ay":-2.70053, "alpha":0.33767, "fx":[-14.69593,-15.33005,-17.52919,-16.84116], "fy":[-34.3455,-33.07531,-32.75466,-34.85118]}, + {"t":4.21158, "x":9.99452, "y":3.74229, "heading":-2.84892, "vx":-0.10301, "vy":-1.22969, "omega":0.99932, "ax":-2.32698, "ay":-1.8724, "alpha":0.28473, "fx":[-27.95106,-28.52084,-30.23962,-29.63746], "fy":[-23.9156,-22.6953,-22.60272,-24.4064]}, + {"t":4.24121, "x":9.99045, "y":3.70503, "heading":-2.8193, "vx":-0.17196, "vy":-1.28517, "omega":1.00776, "ax":-2.95771, "ay":0.40173, "alpha":0.26194, "fx":[-36.13061,-36.55646,-37.81338,-37.3848], "fy":[4.47043,6.2775,5.33716,4.00149]}, + {"t":4.27085, "x":9.98406, "y":3.66713, "heading":-2.78944, "vx":-0.2596, "vy":-1.27327, "omega":1.01552, "ax":-2.90581, "ay":0.6966, "alpha":0.22133, "fx":[-35.60478,-35.97582,-37.04356,-36.66617], "fy":[8.28181,9.74815,8.97539,7.82464]}, + {"t":4.30048, "x":9.97509, "y":3.6297, "heading":-2.75935, "vx":-0.34571, "vy":-1.25263, "omega":1.02208, "ax":-2.8537, "ay":0.89463, "alpha":0.15454, "fx":[-35.14145,-35.43462,-36.20454,-35.90418], "fy":[10.92167,11.88971,11.34409,10.57588]}, + {"t":4.33011, "x":9.96359, "y":3.59298, "heading":-2.72906, "vx":-0.43027, "vy":-1.22612, "omega":1.02666, "ax":-2.78764, "ay":1.0882, "alpha":0.15595, "fx":[-34.35437,-34.62486,-35.34627,-35.05648], "fy":[13.32825,14.40292,13.71317,12.96588]}, + {"t":4.35975, "x":9.94962, "y":3.55712, "heading":-2.69864, "vx":-0.51288, "vy":-1.19387, "omega":1.03128, "ax":-2.70766, "ay":1.27753, "alpha":0.10526, "fx":[-33.51066,-33.70357,-34.19426,-33.97442], "fy":[15.79146,16.54415,15.98258,15.55834]}, + {"t":4.38938, "x":9.93323, "y":3.5223, "heading":-2.66808, "vx":-0.59312, "vy":-1.15601, "omega":1.0344, "ax":-2.60629, "ay":1.4755, "alpha":0.11569, "fx":[-32.2116,-32.423,-32.9614,-32.71855], "fy":[18.26827,19.04695,18.4908,17.96882]}, + {"t":4.41901, "x":9.91451, "y":3.4887, "heading":-2.63743, "vx":-0.67035, "vy":-1.11229, "omega":1.03783, "ax":-2.38914, "ay":1.80744, "alpha":0.0749, "fx":[-29.6388,-29.77316,-30.10955,-29.93546], "fy":[22.4655,23.05053,22.5446,22.31146]}, + {"t":4.44864, "x":9.8936, "y":3.45653, "heading":-2.60667, "vx":-0.74114, "vy":-1.05873, "omega":1.04005, "ax":-2.07743, "ay":2.15945, "alpha":0.10712, "fx":[-25.6539,-25.84383,-26.30394,-26.07005], "fy":[26.82667,27.62716,26.96347,26.55536]}, + {"t":4.47828, "x":9.87072, "y":3.4261, "heading":-2.57585, "vx":-0.8027, "vy":-0.99474, "omega":1.04322, "ax":-1.80945, "ay":2.38918, "alpha":0.06147, "fx":[-22.44113,-22.56111,-22.81356,-22.65646], "fy":[29.75516,30.27488,29.78674,29.642]}, + {"t":4.50791, "x":9.84614, "y":3.39768, "heading":-2.54494, "vx":-0.85632, "vy":-0.92394, "omega":1.04504, "ax":-1.59614, "ay":2.53715, "alpha":0.1022, "fx":[-19.64193,-19.85786,-20.28085,-20.02632], "fy":[31.57489,32.31949,31.66335,31.29977]}, + {"t":4.53754, "x":9.82006, "y":3.37141, "heading":-2.51397, "vx":-0.90362, "vy":-0.84876, "omega":1.04807, "ax":-1.42789, "ay":2.63589, "alpha":0.05651, "fx":[-17.67597,-17.81279,-18.03624,-17.8694], "fy":[32.85821,33.3178,32.86876,32.74954]}, + {"t":4.56717, "x":9.79266, "y":3.34742, "heading":-2.48291, "vx":-0.94593, "vy":-0.77065, "omega":1.04975, "ax":-1.29393, "ay":2.70445, "alpha":0.10132, "fx":[-15.836,-16.10921,-16.52587,-16.22554], "fy":[33.70521,34.36329,33.75591,33.39814]}, + {"t":4.59681, "x":9.76406, "y":3.32577, "heading":-2.45181, "vx":-0.98428, "vy":-0.69051, "omega":1.05275, "ax":-1.18572, "ay":2.75384, "alpha":0.05947, "fx":[-14.61507,-14.80165,-15.0386,-14.83052], "fy":[34.35457,34.77039,34.3512,34.21587]}, + {"t":4.62644, "x":9.73437, "y":3.30652, "heading":-2.42061, "vx":-1.01941, "vy":-0.60891, "omega":1.05451, "ax":-1.09695, "ay":2.79057, "alpha":0.10929, "fx":[-13.31956,-13.67307,-14.11445,-13.74046], "fy":[34.81274,35.44507,34.82311,34.44757]}, + {"t":4.65607, "x":9.70368, "y":3.2897, "heading":-2.38936, "vx":-1.05192, "vy":-0.52621, "omega":1.05775, "ax":-1.02308, "ay":2.81864, "alpha":0.07269, "fx":[-12.51245,-12.78416,-13.07272,-12.78471], "fy":[35.18242,35.61166,35.16032,34.97758]}, + {"t":4.68571, "x":9.67206, "y":3.27534, "heading":-2.35802, "vx":-1.08223, "vy":-0.44269, "omega":1.0599, "ax":-0.9608, "ay":2.8406, "alpha":0.12611, "fx":[-11.53036,-12.00223,-12.4976,-12.00983], "fy":[35.47137,36.11587,35.42938,35.01327]}, + {"t":4.71534, "x":9.63957, "y":3.26347, "heading":-2.32661, "vx":-1.11071, "vy":-0.35852, "omega":1.06364, "ax":-0.89941, "ay":2.8598, "alpha":1.27102, "fx":[-5.87244,-11.33251,-16.60966,-11.15603], "fy":[36.07132,40.86313,35.29668,30.75874]}, + {"t":4.75277, "x":9.59737, "y":3.25205, "heading":-2.2868, "vx":-1.14437, "vy":-0.25147, "omega":1.11122, "ax":-0.81783, "ay":2.88515, "alpha":0.96212, "fx":[-6.15189,-10.46538,-14.29711,-9.97696], "fy":[36.46617,39.89648,35.58682,32.30784]}, + {"t":4.7902, "x":9.55396, "y":3.24466, "heading":-2.24521, "vx":-1.17498, "vy":-0.14348, "omega":1.14723, "ax":-0.71209, "ay":2.91288, "alpha":0.69782, "fx":[-5.97553,-9.20373,-11.83486,-8.59013], "fy":[36.76245,39.22252,35.94107,33.71782]}, + {"t":4.82763, "x":9.50948, "y":3.24133, "heading":-2.20226, "vx":-1.20164, "vy":-0.03445, "omega":1.17335, "ax":-0.57111, "ay":2.94355, "alpha":0.5267, "fx":[-4.96924,-7.47119,-9.3175,-6.79747], "fy":[37.11563,38.94851,36.33936,34.77379]}, + {"t":4.86506, "x":9.4641, "y":3.24211, "heading":-2.15834, "vx":-1.22301, "vy":0.07573, "omega":1.19306, "ax":-0.37567, "ay":2.97452, "alpha":0.38621, "fx":[-3.15306,-5.00869,-6.24642,-4.37523], "fy":[37.41881,38.82638,36.76848,35.71224]}, + {"t":4.90249, "x":9.41806, "y":3.24702, "heading":-2.11369, "vx":-1.23708, "vy":0.18707, "omega":1.20752, "ax":-0.09212, "ay":2.99633, "alpha":0.28151, "fx":[-0.07033,-1.44115,-2.2366,-0.85792], "fy":[37.62529,38.71188,37.08192,36.39723]}, + {"t":4.93992, "x":9.37169, "y":3.25613, "heading":-2.06849, "vx":-1.24052, "vy":0.29923, "omega":1.21806, "ax":0.33704, "ay":2.97815, "alpha":0.21856, "fx":[4.9987,3.95231,3.42959,4.47126], "fy":[37.33417,38.28564,36.88851,36.39929]}, + {"t":4.97735, "x":9.32549, "y":3.26941, "heading":-2.02289, "vx":-1.22791, "vy":0.4107, "omega":1.22624, "ax":0.95794, "ay":2.8391, "alpha":0.1441, "fx":[12.4556,11.76284,11.50383,12.17469], "fy":[35.52657,36.25842,35.21036,34.95949]}, + {"t":5.01479, "x":9.2802, "y":3.28677, "heading":-1.977, "vx":-1.19205, "vy":0.51697, "omega":1.23163, "ax":1.30476, "ay":2.69611, "alpha":0.13097, "fx":[16.70582,16.10501,15.93101,16.49621], "fy":[33.72298,34.46133,33.42417,33.19724]}, + {"t":5.05222, "x":9.2365, "y":3.30801, "heading":-1.93089, "vx":-1.14321, "vy":0.61789, "omega":1.23654, "ax":1.53436, "ay":2.57038, "alpha":0.07147, "fx":[19.35392,19.05712,19.02526,19.28185], "fy":[32.06199,32.66647,31.91466,31.8759]}, + {"t":5.08965, "x":9.19478, "y":3.33294, "heading":-1.88461, "vx":-1.08578, "vy":0.7141, "omega":1.23921, "ax":1.74866, "ay":2.42612, "alpha":0.08959, "fx":[22.07099,21.71002,21.66452,21.9873], "fy":[30.30164,30.95774,30.0766,29.96977]}, + {"t":5.12708, "x":9.15536, "y":3.36137, "heading":-1.83823, "vx":-1.02033, "vy":0.80491, "omega":1.24256, "ax":1.94747, "ay":2.2625, "alpha":0.03794, "fx":[24.3656,24.29423,24.3443,24.36932], "fy":[28.09762,28.79264,28.09072,28.14398]}, + {"t":5.16451, "x":9.11854, "y":3.39309, "heading":-1.79171, "vx":-0.94743, "vy":0.8896, "omega":1.24398, "ax":2.12588, "ay":2.07873, "alpha":0.07793, "fx":[26.71139,26.45237,26.45357,26.67671], "fy":[25.91977,26.64226,25.71862,25.65566]}, + {"t":5.20194, "x":9.08456, "y":3.42784, "heading":-1.74515, "vx":-0.86786, "vy":0.96741, "omega":1.2469, "ax":2.26806, "ay":1.86799, "alpha":0.01482, "fx":[28.29717,28.36905,28.41457,28.32221], "fy":[23.0963,23.80947,23.2138,23.28001]}, + {"t":5.23937, "x":9.05367, "y":3.46536, "heading":-1.69848, "vx":-0.78296, "vy":1.03733, "omega":1.24746, "ax":2.25049, "ay":1.56331, "alpha":0.07013, "fx":[28.2526,28.02242,28.01499,28.23428], "fy":[19.53231,20.10552,19.28249,19.24528]}, + {"t":5.2768, "x":9.02594, "y":3.50528, "heading":-1.65179, "vx":-0.69873, "vy":1.09585, "omega":1.25008, "ax":0.8977, "ay":0.55341, "alpha":-0.03226, "fx":[11.13021,11.28167,11.31272,11.16034], "fy":[6.78996,6.82473,7.00356,7.05237]}, + {"t":5.31423, "x":9.00041, "y":3.54669, "heading":-1.60499, "vx":-0.66512, "vy":1.11656, "omega":1.24887, "ax":0.17433, "ay":0.10316, "alpha":0.04704, "fx":[2.30816,2.05456,2.05026,2.30366], "fy":[1.47229,1.40035,1.14685,1.13848]}, + {"t":5.35166, "x":8.97564, "y":3.58856, "heading":-1.55825, "vx":-0.6586, "vy":1.12042, "omega":1.25063, "ax":-0.01687, "ay":-0.00992, "alpha":-0.04673, "fx":[-0.30859,-0.12977,-0.11322,-0.29202], "fy":[-0.22799,-0.38494,0.04835,0.0684]}, + {"t":5.38909, "x":8.95097, "y":3.63049, "heading":-1.51144, "vx":-0.65923, "vy":1.12005, "omega":1.24889, "ax":-0.02729, "ay":-0.01608, "alpha":0.0502, "fx":[-0.21814,-0.48307,-0.46421,-0.19928], "fy":[0.00537,-0.09345,-0.36987,-0.3461]}, + {"t":5.42652, "x":8.92628, "y":3.6724, "heading":-1.46469, "vx":-0.66025, "vy":1.11945, "omega":1.25076, "ax":-0.01424, "ay":-0.0084, "alpha":-0.04628, "fx":[-0.27343,-0.07871,-0.08261,-0.27733], "fy":[-0.2507,-0.30678,0.07492,0.06236]}, + {"t":5.46396, "x":8.90156, "y":3.7143, "heading":-1.41787, "vx":-0.66078, "vy":1.11913, "omega":1.24903, "ax":-0.00019, "ay":-0.00011, "alpha":0.05046, "fx":[0.10358,-0.14973,-0.10827,0.14505], "fy":[0.20514,0.11361,-0.18943,-0.13485]}, + {"t":5.50139, "x":8.87682, "y":3.75619, "heading":-1.37112, "vx":-0.66079, "vy":1.11913, "omega":1.25092, "ax":0.00343, "ay":0.00202, "alpha":-0.04609, "fx":[-0.04455,0.15654,0.13027,-0.07082], "fy":[-0.14521,-0.13816,0.21535,0.16923]}, + {"t":5.53882, "x":8.85209, "y":3.79808, "heading":-1.3243, "vx":-0.66066, "vy":1.11921, "omega":1.2492, "ax":0.00428, "ay":0.00253, "alpha":0.04664, "fx":[0.1371,-0.08847,-0.03006,0.19551], "fy":[0.23,0.12839,-0.15526,-0.07678]}, + {"t":5.57625, "x":8.82736, "y":3.83997, "heading":-1.27754, "vx":-0.6605, "vy":1.1193, "omega":1.25094, "ax":0.00267, "ay":0.00157, "alpha":-0.04491, "fx":[-0.04142,0.15588,0.10808,-0.08922], "fy":[-0.16268,-0.11128,0.21471,0.13792]}, + {"t":5.61368, "x":8.80264, "y":3.88187, "heading":-1.23071, "vx":-0.6604, "vy":1.11936, "omega":1.24926, "ax":0.00164, "ay":0.00096, "alpha":0.04037, "fx":[0.08041,-0.10642,-0.03952,0.14731], "fy":[0.19043,0.08542,-0.15965,-0.06796]}, + {"t":5.65111, "x":8.77792, "y":3.92377, "heading":-1.18395, "vx":-0.66034, "vy":1.1194, "omega":1.25077, "ax":0.0005, "ay":0.00029, "alpha":-0.04262, "fx":[-0.05343,0.13259,0.06582,-0.1202], "fy":[-0.18189,-0.0928,0.19564,0.09368]}, + {"t":5.68854, "x":8.75321, "y":3.96567, "heading":-1.13714, "vx":-0.66032, "vy":1.11941, "omega":1.24918, "ax":0.00004, "ay":0.00003, "alpha":0.03223, "fx":[0.03837,-0.10215,-0.03725,0.10327], "fy":[0.14668,0.05258,-0.14478,-0.05316]}, + {"t":5.72597, "x":8.72849, "y":4.00757, "heading":-1.09038, "vx":-0.66032, "vy":1.11941, "omega":1.25038, "ax":-0.00072, "ay":-0.00043, "alpha":-0.04015, "fx":[-0.0534,0.1189,0.03528,-0.13702], "fy":[-0.18927,-0.06759,0.17862,0.05687]}, + {"t":5.7634, "x":8.70377, "y":4.04947, "heading":-1.04357, "vx":-0.66035, "vy":1.11939, "omega":1.24888, "ax":-0.00151, "ay":-0.00089, "alpha":0.02214, "fx":[0.0002,-0.08794,-0.0379,0.05025], "fy":[0.09178,0.02438,-0.11823,-0.0424]}, + {"t":5.80083, "x":8.67906, "y":4.09137, "heading":-0.99683, "vx":-0.6604, "vy":1.11936, "omega":1.24971, "ax":-0.0028, "ay":-0.00165, "alpha":-0.03898, "fx":[-0.06553,0.09754,-0.00459,-0.16766], "fy":[-0.20427,-0.05223,0.15697,0.01679]}, + {"t":5.83826, "x":8.65433, "y":4.13327, "heading":-0.95005, "vx":-0.66051, "vy":1.1193, "omega":1.24825, "ax":-0.0039, "ay":-0.0023, "alpha":0.00941, "fx":[-0.04333,-0.07193,-0.05407,-0.02548], "fy":[0.01741,-0.00393,-0.08426,-0.04418]}, + {"t":5.8757, "x":8.62961, "y":4.17516, "heading":-0.90333, "vx":-0.66066, "vy":1.11921, "omega":1.2486, "ax":-0.00319, "ay":-0.00188, "alpha":-0.04133, "fx":[-0.05779,0.10951,-0.02194,-0.18925], "fy":[-0.21875,-0.02662,0.15919,-0.00796]}, + {"t":5.91313, "x":8.60488, "y":4.21705, "heading":-0.85659, "vx":-0.66078, "vy":1.11914, "omega":1.24705, "ax":0.00115, "ay":0.00068, "alpha":-0.00785, "fx":[0.01356,0.05672,0.01509,-0.02808], "fy":[-0.02367,0.03604,0.02322,-0.00177]}, + {"t":5.95056, "x":8.58014, "y":4.25894, "heading":-0.80991, "vx":-0.66073, "vy":1.11916, "omega":1.24676, "ax":0.01441, "ay":0.0085, "alpha":-0.05093, "fx":[0.17671,0.37362,0.18353,-0.01337], "fy":[-0.13275,0.14499,0.31748,0.09541]}, + {"t":5.98799, "x":8.55542, "y":4.30084, "heading":-0.76325, "vx":-0.66019, "vy":1.11948, "omega":1.24485, "ax":0.02614, "ay":0.0154, "alpha":-0.0339, "fx":[0.33299,0.47067,0.32041,0.18274], "fy":[0.03952,0.25902,0.30582,0.16553]}, + {"t":6.02542, "x":8.53073, "y":4.34275, "heading":-0.71665, "vx":-0.65921, "vy":1.12006, "omega":1.24359, "ax":0.00755, "ay":0.00444, "alpha":-0.07462, "fx":[0.11723,0.38508,0.07151,-0.19629], "fy":[-0.29217,0.17831,0.33853,-0.00255]}, + {"t":6.06285, "x":8.50606, "y":4.38468, "heading":-0.6701, "vx":-0.65893, "vy":1.12023, "omega":1.24079, "ax":-0.20326, "ay":-0.12049, "alpha":-0.07686, "fx":[-2.50024,-2.22878,-2.58135,-2.8526], "fy":[-1.83818,-1.39396,-1.22193,-1.57054]}, + {"t":6.10028, "x":8.48125, "y":4.42653, "heading":-0.62366, "vx":-0.66654, "vy":1.11572, "omega":1.23791, "ax":-0.97326, "ay":-0.60346, "alpha":-0.12025, "fx":[-12.08101,-11.68617,-12.25112,-12.6445], "fy":[-8.02148,-7.52443,-7.02115,-7.60584]}, + {"t":6.13771, "x":8.45562, "y":4.46787, "heading":-0.57732, "vx":-0.70297, "vy":1.09313, "omega":1.23341, "ax":-2.27413, "ay":-1.59468, "alpha":-0.14056, "fx":[-28.29158,-27.84071,-28.56637,-29.00794], "fy":[-20.40495,-20.17069,-19.22281,-19.93564]}, + {"t":6.17514, "x":8.42772, "y":4.50767, "heading":-0.53115, "vx":-0.78809, "vy":1.03344, "omega":1.22815, "ax":-2.26168, "ay":-1.88185, "alpha":-0.19364, "fx":[-28.03975,-27.46674,-28.51271,-29.06499], "fy":[-24.16341,-23.88427,-22.51016,-23.5349]}, + {"t":6.21257, "x":8.39663, "y":4.54503, "heading":-0.48518, "vx":-0.87275, "vy":0.963, "omega":1.2209, "ax":-2.11607, "ay":-2.0903, "alpha":-0.25481, "fx":[-26.09593,-25.41484,-26.82212,-27.47072], "fy":[-27.03131,-26.2744,-24.93426,-26.27513]}, + {"t":6.25, "x":8.36248, "y":4.57961, "heading":-0.43948, "vx":-0.95196, "vy":0.88476, "omega":1.21137, "ax":-1.93617, "ay":-2.27277, "alpha":-0.34621, "fx":[-23.65141,-22.80987,-24.77889,-25.56854], "fy":[-29.63473,-28.49101,-26.82923,-28.68371]}, + {"t":6.28743, "x":8.32549, "y":4.61114, "heading":-0.39414, "vx":-1.02443, "vy":0.79968, "omega":1.19841, "ax":-1.73633, "ay":-2.43523, "alpha":-0.46158, "fx":[-20.88304,-19.87962,-22.55726,-23.49681], "fy":[-32.07587,-30.30078,-28.45017,-30.93473]}, + {"t":6.32487, "x":8.28593, "y":4.63937, "heading":-0.34928, "vx":-1.08942, "vy":0.70853, "omega":1.18113, "ax":-1.52112, "ay":-2.57839, "alpha":-0.62735, "fx":[-17.79737,-16.60566,-20.26549,-21.38747], "fy":[-34.46602,-31.62459,-29.72693,-33.10203]}, + {"t":6.3623, "x":8.24409, "y":4.66408, "heading":-0.30507, "vx":-1.14636, "vy":0.61202, "omega":1.15765, "ax":-1.28289, "ay":-2.70668, "alpha":-0.84104, "fx":[-14.28105,-12.85352,-17.83505,-19.17474], "fy":[-36.7601,-32.71233,-30.66337,-35.19828]}, + {"t":6.39973, "x":8.20028, "y":4.68509, "heading":-0.26174, "vx":-1.19438, "vy":0.51071, "omega":1.12617, "ax":-0.75422, "ay":-2.89996, "alpha":-1.13012, "fx":[-6.94376,-5.19463,-11.97486,-13.59784], "fy":[-40.04665,-34.38484,-32.22266,-38.34378]}, + {"t":6.43716, "x":8.15505, "y":4.70218, "heading":-0.21959, "vx":-1.22261, "vy":0.40216, "omega":1.08387, "ax":-0.15281, "ay":-2.99335, "alpha":-1.51178, "fx":[1.55552,3.67662,-5.47881,-7.39383], "fy":[-42.31794,-34.53352,-32.27693,-40.53925]}, + {"t":6.47459, "x":8.10918, "y":4.71513, "heading":-0.17902, "vx":-1.22833, "vy":0.29011, "omega":1.02728, "ax":0.2312, "ay":-2.98888, "alpha":-2.01857, "fx":[7.69731,10.21408,-2.09973,-4.25181], "fy":[-43.69456,-33.0529,-30.78286,-41.91391]}, + {"t":6.51202, "x":8.06336, "y":4.7239, "heading":-0.14056, "vx":-1.21967, "vy":0.17824, "omega":0.95172, "ax":0.48263, "ay":-2.9591, "alpha":-2.65997, "fx":[12.6716,15.55346,-0.91204,-3.18135], "fy":[-44.81835,-30.85862,-28.70541,-43.57262]}, + {"t":6.54945, "x":8.01804, "y":4.7285, "heading":-0.10494, "vx":-1.20161, "vy":0.06748, "omega":0.85216, "ax":0.6562, "ay":-2.92579, "alpha":-3.49215, "fx":[17.21044,20.50557,-1.35461,-3.55127], "fy":[-46.73064,-28.04012,-26.12414,-45.39482]}, + {"t":6.58688, "x":7.97353, "y":4.72897, "heading":-0.07304, "vx":-1.17705, "vy":-0.04204, "omega":0.72144, "ax":0.78191, "ay":-2.89495, "alpha":-4.56379, "fx":[21.80241,25.5591,-3.21955,-5.04654], "fy":[-49.08523,-24.45761,-22.91347,-48.29116]}, + {"t":6.62431, "x":7.93002, "y":4.72537, "heading":-0.04604, "vx":-1.14778, "vy":-0.1504, "omega":0.55062, "ax":0.87661, "ay":-2.86786, "alpha":-5.89041, "fx":[26.70803,31.05937,-6.43479,-7.502], "fy":[-52.05537,-20.14394,-19.11946,-52.07417]}, + {"t":6.66174, "x":7.88767, "y":4.71773, "heading":-0.02543, "vx":-1.11497, "vy":-0.25775, "omega":0.33013, "ax":0.95027, "ay":-2.84443, "alpha":-7.49248, "fx":[32.03173,37.27414,-10.97167,-10.82063], "fy":[-55.70818,-15.10327,-14.63236,-56.77785]}, + {"t":6.69917, "x":7.8466, "y":4.70609, "heading":-0.01307, "vx":-1.0794, "vy":-0.36422, "omega":0.04968, "ax":0.98717, "ay":-2.82529, "alpha":-1.0762, "fx":[15.30673,15.91985,9.1752,8.9565], "fy":[-38.22134,-32.28843,-32.4042,-38.35041]}, + {"t":6.70945, "x":7.83556, "y":4.7022, "heading":-0.01256, "vx":-1.06926, "vy":-0.39324, "omega":0.03863, "ax":1.00617, "ay":-2.8223, "alpha":-0.73214, "fx":[14.58603,15.02466,10.43376,10.26404], "fy":[-37.24983,-33.21087,-33.30814,-37.346]}, + {"t":6.71972, "x":7.82463, "y":4.69801, "heading":-0.01217, "vx":-1.05892, "vy":-0.42224, "omega":0.0311, "ax":1.02497, "ay":-2.81541, "alpha":-0.50656, "fx":[14.16354,14.55746,11.32332,11.2041], "fy":[-36.55036,-33.76611,-33.83889,-36.61512]}, + {"t":6.73, "x":7.8138, "y":4.69353, "heading":-0.01185, "vx":-1.04839, "vy":-0.45116, "omega":0.0259, "ax":1.04483, "ay":-2.80798, "alpha":-0.35106, "fx":[13.96577,14.31214,12.02298,11.94066], "fy":[-36.03561,-34.11463,-34.16944,-36.0792]}, + {"t":6.74027, "x":7.80309, "y":4.68874, "heading":-0.01158, "vx":-1.03765, "vy":-0.48001, "omega":0.02229, "ax":1.06585, "ay":-2.79994, "alpha":-0.24344, "fx":[13.92514,14.22656,12.59849,12.54247], "fy":[-35.64379,-34.31947,-34.36055,-35.67301]}, + {"t":6.75054, "x":7.79248, "y":4.68366, "heading":-0.01135, "vx":-1.0267, "vy":-0.50878, "omega":0.01979, "ax":1.08812, "ay":-2.79122, "alpha":-0.16916, "fx":[13.99218,14.26826,13.09136,13.05402], "fy":[-35.33278,-34.42231,-34.454,-35.35203]}, + {"t":6.76082, "x":7.78199, "y":4.67829, "heading":-0.01115, "vx":-1.01552, "vy":-0.53746, "omega":0.01805, "ax":1.11173, "ay":-2.78175, "alpha":-0.11985, "fx":[14.12585,14.44038,13.52227,13.49824], "fy":[-35.074,-34.449,-34.47836,-35.0863]}, + {"t":6.77109, "x":7.77162, "y":4.67262, "heading":-0.01096, "vx":-1.0041, "vy":-0.56604, "omega":0.01682, "ax":1.13684, "ay":-2.77143, "alpha":-0.08421, "fx":[14.33537,14.64605,13.93763,13.92285], "fy":[-34.84683,-34.42269,-34.44791,-34.8542]}, + {"t":6.78137, "x":7.76136, "y":4.66666, "heading":-0.01079, "vx":-0.99242, "vy":-0.59451, "omega":0.01596, "ax":1.16354, "ay":-2.76016, "alpha":-0.05941, "fx":[14.59687,14.90438,14.34201,14.33368], "fy":[-34.63765,-34.35317,-34.3757,-34.64156]}, + {"t":6.79164, "x":7.75123, "y":4.6604, "heading":-0.01063, "vx":-0.98047, "vy":-0.62287, "omega":0.01535, "ax":1.19201, "ay":-2.74781, "alpha":-0.04295, "fx":[14.89741,15.2223,14.74223,14.73841], "fy":[-34.43555,-34.24859,-34.26925,-34.437]}, + {"t":6.80191, "x":7.74122, "y":4.65386, "heading":-0.01047, "vx":-0.96822, "vy":-0.6511, "omega":0.01491, "ax":1.22238, "ay":-2.73424, "alpha":-0.02973, "fx":[15.2478,15.54715,15.16245,15.16182], "fy":[-34.23227,-34.11476,-34.13287,-34.23192]}, + {"t":6.81219, "x":7.73133, "y":4.64703, "heading":-0.01031, "vx":-0.95566, "vy":-0.67919, "omega":0.0146, "ax":1.25487, "ay":-2.71927, "alpha":-0.02105, "fx":[15.62792,15.92742,15.59311,15.59482], "fy":[-34.02134,-33.95273,-33.97003,-34.01962]}, + {"t":6.82246, "x":7.72158, "y":4.6399, "heading":-0.01016, "vx":-0.94277, "vy":-0.70713, "omega":0.01438, "ax":1.28967, "ay":-2.70272, "alpha":-0.01518, "fx":[16.04011,16.35341,16.04331,16.04681], "fy":[-33.79684,-33.76376,-33.78118,-33.79398]}, + {"t":6.83274, "x":7.71196, "y":4.6325, "heading":-0.01002, "vx":-0.92952, "vy":-0.7349, "omega":0.01423, "ax":1.327, "ay":-2.68434, "alpha":-0.01096, "fx":[16.48629,16.81957,16.51968,16.52468], "fy":[-33.55362,-33.54797,-33.56563,-33.54974]}, + {"t":6.84301, "x":7.70248, "y":4.62481, "heading":-0.00987, "vx":-0.91588, "vy":-0.76248, "omega":0.01412, "ax":1.36715, "ay":-2.66385, "alpha":-0.00698, "fx":[16.97247,17.31445,17.03212,17.03851], "fy":[-33.28622,-33.30356,-33.32146,-33.28132]}, + {"t":6.85329, "x":7.69315, "y":4.61683, "heading":-0.00973, "vx":-0.90184, "vy":-0.78985, "omega":0.01404, "ax":1.41036, "ay":-2.64094, "alpha":-0.00899, "fx":[17.46562,17.94245,17.55101,17.5589], "fy":[-32.99128,-33.02198,-33.0485,-32.98525]}, + {"t":6.86356, "x":7.68395, "y":4.60858, "heading":-0.00958, "vx":-0.88735, "vy":-0.81698, "omega":0.01395, "ax":1.45699, "ay":-2.61519, "alpha":-0.00681, "fx":[18.03546,18.52802,18.13851,18.14742], "fy":[-32.66235,-32.70724,-32.7344,-32.65545]}, + {"t":6.87383, "x":7.67491, "y":4.60004, "heading":-0.00944, "vx":-0.87238, "vy":-0.84385, "omega":0.01388, "ax":1.50734, "ay":-2.58615, "alpha":-0.00607, "fx":[18.6523,19.17057,18.7672,18.77681], "fy":[-32.29497,-32.34834,-32.37669,-32.28742]}, + {"t":6.88411, "x":7.66603, "y":4.59124, "heading":-0.0093, "vx":-0.85689, "vy":-0.87042, "omega":0.01382, "ax":1.56184, "ay":-2.55322, "alpha":-0.00208, "fx":[19.34484,19.80286,19.46707,19.47716], "fy":[-31.87948,-31.94321,-31.96695,-31.87141]}, + {"t":6.89438, "x":7.65731, "y":4.58216, "heading":-0.00915, "vx":-0.84085, "vy":-0.89665, "omega":0.0138, "ax":1.62084, "ay":-2.51576, "alpha":-0.00079, "fx":[20.07919,20.53443,20.2089,20.21941], "fy":[-31.40847,-31.47743,-31.50197,-31.39992]}, + {"t":6.90466, "x":7.64876, "y":4.57282, "heading":-0.00901, "vx":-0.82419, "vy":-0.9225, "omega":0.01379, "ax":1.68483, "ay":-2.47289, "alpha":-0.00127, "fx":[20.86434,21.36106,21.00248,21.01343], "fy":[-30.8696,-30.94399,-30.97031,-30.86054]}, + {"t":6.91493, "x":7.64038, "y":4.56321, "heading":-0.00887, "vx":-0.80688, "vy":-0.9479, "omega":0.01378, "ax":1.75419, "ay":-2.42365, "alpha":-0.00268, "fx":[21.71004,22.27311,21.8575,21.86891], "fy":[-30.2506,-30.33127,-30.35964,-30.24103]}, + {"t":6.9252, "x":7.63218, "y":4.55334, "heading":-0.00873, "vx":-0.78886, "vy":-0.9728, "omega":0.01375, "ax":1.82929, "ay":-2.36689, "alpha":-0.00399, "fx":[22.62784,23.2548,22.78508,22.79697], "fy":[-29.53787,-29.62292,-29.6559,-29.52777]}, + {"t":6.93548, "x":7.62417, "y":4.54322, "heading":-0.00859, "vx":-0.77007, "vy":-0.99712, "omega":0.01371, "ax":1.9105, "ay":-2.30117, "alpha":-0.00149, "fx":[23.64472,24.24725,23.81049,23.8228], "fy":[-28.71269,-28.80515,-28.83865,-28.70211]}, + {"t":6.94575, "x":7.61636, "y":4.53286, "heading":-0.00845, "vx":-0.75044, "vy":-1.02076, "omega":0.01369, "ax":1.99788, "ay":-2.22499, "alpha":-0.00274, "fx":[24.71716,25.38124,24.89136,24.90404], "fy":[-27.75669,-27.85634,-27.8906,-27.74567]}, + {"t":6.95603, "x":7.60876, "y":4.52225, "heading":-0.00831, "vx":-0.72991, "vy":-1.04362, "omega":0.01366, "ax":2.09127, "ay":-2.13658, "alpha":-0.00956, "fx":[25.83599,26.67759,26.01856,26.03156], "fy":[-26.65093,-26.74591,-26.79273,-26.63951]}, + {"t":6.9663, "x":7.60137, "y":4.51142, "heading":-0.00816, "vx":-0.70843, "vy":-1.06557, "omega":0.01357, "ax":2.18984, "ay":-2.03446, "alpha":-0.00776, "fx":[27.07597,27.88257,27.26024,27.27321], "fy":[-25.3737,-25.47058,-25.51647,-25.36213]}, + {"t":6.97657, "x":7.59421, "y":4.50036, "heading":-0.00803, "vx":-0.68593, "vy":-1.08648, "omega":0.01349, "ax":2.2919, "ay":-1.91763, "alpha":-0.01582, "fx":[28.31129,29.28675,28.4921,28.50473], "fy":[-23.91571,-24.0075,-24.05395,-23.90424]}, + {"t":6.98685, "x":7.58728, "y":4.4891, "heading":-0.00789, "vx":-0.66238, "vy":-1.10618, "omega":0.01332, "ax":2.39429, "ay":-1.78684, "alpha":0.00406, "fx":[29.71492,30.21843,29.88464,29.89675], "fy":[-22.27855,-22.39087,-22.40513,-22.26739]}, + {"t":6.99712, "x":7.5806, "y":4.47764, "heading":-0.00775, "vx":-0.63778, "vy":-1.12454, "omega":0.01337, "ax":2.49171, "ay":-1.64678, "alpha":0.00012, "fx":[30.90794,31.50521,31.08008,31.09204], "fy":[-20.52827,-20.63731,-20.6563,-20.51715]}, + {"t":7.0074, "x":7.57418, "y":4.466, "heading":-0.00761, "vx":-0.61218, "vy":-1.14146, "omega":0.01337, "ax":2.57713, "ay":-1.50785, "alpha":0.00325, "fx":[31.97689,32.54575,32.16085,32.17303], "fy":[-18.78669,-18.90395,-18.92663,-18.77543]}, + {"t":7.01767, "x":7.56803, "y":4.45419, "heading":-0.00748, "vx":-0.5857, "vy":-1.15695, "omega":0.0134, "ax":2.64432, "ay":-1.38464, "alpha":0.00163, "fx":[32.77535,33.46693,32.98041,32.99311], "fy":[-17.23587,-17.3737,-17.398,-17.22434]}, + {"t":7.02794, "x":7.56215, "y":4.44223, "heading":-0.00734, "vx":-0.55854, "vy":-1.17117, "omega":0.01342, "ax":2.69315, "ay":-1.28474, "alpha":0.01247, "fx":[33.4018,33.96866,33.63672,33.65018], "fy":[-15.97097,-16.14191,-16.16518,-15.95911]}, + {"t":7.03822, "x":7.55655, "y":4.43013, "heading":-0.0072, "vx":-0.53087, "vy":-1.18437, "omega":0.01355, "ax":2.72939, "ay":-1.20313, "alpha":-0.01606, "fx":[33.6321,34.99964,33.91158,33.92594], "fy":[-14.93746,-15.11494,-15.17863,-14.92532]}, + {"t":7.04849, "x":7.55124, "y":4.4179, "heading":-0.00706, "vx":-0.50282, "vy":-1.19673, "omega":0.01338, "ax":2.7588, "ay":-1.13088, "alpha":-0.01972, "fx":[33.93021,35.51434,34.2405,34.2552], "fy":[-14.01655,-14.23241,-14.29056,-14.00455]}, + {"t":7.05877, "x":7.54622, "y":4.40554, "heading":-0.00692, "vx":-0.47448, "vy":-1.20835, "omega":0.01318, "ax":2.78454, "ay":-1.06226, "alpha":-0.01255, "fx":[34.25904,35.77128,34.59104,34.60562], "fy":[-13.14588,-13.39031,-13.44232,-13.13437]}, + {"t":7.06904, "x":7.54149, "y":4.39307, "heading":-0.00679, "vx":-0.44587, "vy":-1.21927, "omega":0.01305, "ax":2.80789, "ay":-0.99459, "alpha":-0.00061, "fx":[34.59255,35.90247,34.94259,34.95675], "fy":[-12.29029,-12.55529,-12.60451,-12.27954]}, + {"t":7.07931, "x":7.53706, "y":4.38049, "heading":-0.00665, "vx":-0.41702, "vy":-1.22948, "omega":0.01304, "ax":2.82932, "ay":-0.92681, "alpha":-0.00381, "fx":[34.83032,36.24705,35.18766,35.20076], "fy":[-11.43745,-11.71592,-11.75902,-11.42795]}, + {"t":7.08959, "x":7.53292, "y":4.36781, "heading":-0.00652, "vx":-0.38795, "vy":-1.23901, "omega":0.013, "ax":2.84913, "ay":-0.85794, "alpha":-0.01755, "fx":[34.99926,36.73435,35.35575,35.36731], "fy":[-10.57468,-10.85951,-10.8962,-10.56686]}, + {"t":7.09986, "x":7.52909, "y":4.35504, "heading":-0.00639, "vx":-0.35868, "vy":-1.24782, "omega":0.01282, "ax":2.86823, "ay":-0.78455, "alpha":0.03232, "fx":[35.54222,36.08602,35.88682,35.8964], "fy":[-9.66018,-9.94241,-9.97069,-9.65438]}, + {"t":7.11014, "x":7.52556, "y":4.34218, "heading":-0.00625, "vx":-0.32921, "vy":-1.25588, "omega":0.01315, "ax":2.89069, "ay":-0.68829, "alpha":0.02478, "fx":[35.79394,36.47711,36.12817,36.13535], "fy":[-8.4586,-8.74032,-8.76035,-8.45534]}, + {"t":7.12041, "x":7.52233, "y":4.32924, "heading":-0.00612, "vx":-0.29952, "vy":-1.26295, "omega":0.01341, "ax":2.92947, "ay":-0.48465, "alpha":0.01699, "fx":[36.25116,37.0722,36.57291,36.57716], "fy":[-5.91495,-6.19633,-6.20617,-5.91489]}, + {"t":7.13068, "x":7.5194, "y":4.31624, "heading":-0.00598, "vx":-0.26942, "vy":-1.26793, "omega":0.01358, "ax":2.96737, "ay":-0.02006, "alpha":0.00727, "fx":[36.68823,37.6872,36.99623,36.99694], "fy":[-0.10963,-0.39139,-0.38865,-0.1135]}, + {"t":7.14096, "x":7.51679, "y":4.30321, "heading":-0.00584, "vx":-0.23893, "vy":-1.26814, "omega":0.01366, "ax":2.89859, "ay":0.63378, "alpha":0.00662, "fx":[35.84791,36.80447,36.14013,36.13705], "fy":[8.05988,7.78016,7.797,8.05179]}, + {"t":7.15123, "x":7.51449, "y":4.29021, "heading":-0.0057, "vx":-0.20915, "vy":-1.26163, "omega":0.01373, "ax":2.67925, "ay":1.27842, "alpha":0.0099, "fx":[33.15363,33.96042,33.42732,33.42113], "fy":[16.11096,15.84078,15.86954,16.09948]}, + {"t":7.16151, "x":7.51248, "y":4.27732, "heading":-0.00556, "vx":-0.18162, "vy":-1.24849, "omega":0.01383, "ax":2.3636, "ay":1.80083, "alpha":0.01146, "fx":[29.25309,29.92732,29.5037,29.49589], "fy":[22.62957,22.3804,22.41506,22.6166]}, + {"t":7.17178, "x":7.51074, "y":4.26459, "heading":-0.00542, "vx":-0.15734, "vy":-1.22999, "omega":0.01395, "ax":2.03507, "ay":2.16963, "alpha":0.01158, "fx":[25.19155,25.74323,25.41312,25.40535], "fy":[27.22367,27.00588,27.04072,27.21127]}, + {"t":7.18205, "x":7.50923, "y":4.25206, "heading":-0.00528, "vx":-0.13643, "vy":-1.2077, "omega":0.01406, "ax":1.73419, "ay":2.42062, "alpha":-0.01283, "fx":[21.34013,22.3208,21.52746,21.52088], "fy":[30.34304,30.16149,30.19408,30.33263]}, + {"t":7.19233, "x":7.50792, "y":4.23978, "heading":-0.00513, "vx":-0.11861, "vy":-1.18283, "omega":0.01393, "ax":1.481, "ay":2.58633, "alpha":-0.00707, "fx":[18.27589,18.94255,18.41811,18.41331], "fy":[32.38963,32.26237,32.28277,32.38192]}, + {"t":7.2026, "x":7.50678, "y":4.22777, "heading":-0.00499, "vx":-0.1034, "vy":-1.15626, "omega":0.01386, "ax":1.27195, "ay":2.69773, "alpha":-0.00645, "fx":[15.7279,16.21645,15.82814,15.8249], "fy":[33.76037,33.67966,33.69166,33.75506]}, + {"t":7.21288, "x":7.50579, "y":4.21603, "heading":-0.00485, "vx":-0.09033, "vy":-1.12854, "omega":0.01379, "ax":1.09931, "ay":2.77454, "alpha":-0.00139, "fx":[13.65531,13.87757,13.71733,13.7153], "fy":[34.70072,34.66307,34.666,34.69733]}, + {"t":7.22315, "x":7.50492, "y":4.20458, "heading":-0.0047, "vx":-0.07904, "vy":-1.10004, "omega":0.01378, "ax":0.95658, "ay":2.82854, "alpha":0.00743, "fx":[11.96832,11.86437,11.99866,11.99749], "fy":[35.35986,35.3573,35.35208,35.35789]}, + {"t":7.23343, "x":7.50415, "y":4.19343, "heading":-0.00456, "vx":-0.06921, "vy":-1.07098, "omega":0.01386, "ax":0.83777, "ay":2.86731, "alpha":0.01373, "fx":[10.54767,10.22443,10.55847,10.55781], "fy":[35.83525,35.85444,35.84189,35.83415]}, + {"t":7.2437, "x":7.50349, "y":4.18258, "heading":-0.00442, "vx":-0.0606, "vy":-1.04152, "omega":0.014, "ax":0.73742, "ay":2.89587, "alpha":-0.00569, "fx":[9.17564,9.32394,9.18594,9.18538], "fy":[36.19797,36.19782,36.20043,36.1971]}, + {"t":7.25397, "x":7.5029, "y":4.17203, "heading":-0.00428, "vx":-0.05302, "vy":-1.01176, "omega":0.01394, "ax":0.65227, "ay":2.91718, "alpha":-0.00444, "fx":[8.11738,8.24241,8.12697,8.12651], "fy":[36.46599,36.46279,36.46466,36.46532]}, + {"t":7.26425, "x":7.50239, "y":4.16179, "heading":-0.00413, "vx":-0.04632, "vy":-0.98179, "omega":0.01389, "ax":0.579, "ay":2.93341, "alpha":-0.00658, "fx":[7.1879,7.36868,7.19688,7.1965], "fy":[36.6707,36.6635,36.66608,36.67018]}, + {"t":7.27452, "x":7.50195, "y":4.15186, "heading":-0.00399, "vx":-0.04037, "vy":-0.95165, "omega":0.01383, "ax":0.51551, "ay":2.94593, "alpha":-0.00615, "fx":[6.39887,6.56626,6.40537,6.40506], "fy":[36.8275,36.82014,36.82187,36.82713]}, + {"t":7.2848, "x":7.50156, "y":4.14223, "heading":-0.00385, "vx":-0.03508, "vy":-0.92139, "omega":0.01376, "ax":0.46006, "ay":2.95571, "alpha":-0.00487, "fx":[5.71742,5.84563,5.72013,5.71987], "fy":[36.94919,36.94325,36.94429,36.94896]}, + {"t":7.29507, "x":7.50122, "y":4.13292, "heading":-0.00371, "vx":-0.03035, "vy":-0.89102, "omega":0.01371, "ax":0.41131, "ay":2.96343, "alpha":-0.00483, "fx":[5.11363,5.22848,5.11189,5.11169], "fy":[37.04462,37.04094,37.04144,37.04451]}, + {"t":7.30534, "x":7.50093, "y":4.12393, "heading":-0.00357, "vx":-0.02613, "vy":-0.86057, "omega":0.01366, "ax":0.36806, "ay":2.96959, "alpha":-0.00548, "fx":[4.57512,4.69083,4.56868,4.56852], "fy":[37.12035,37.11936,37.11946,37.12035]}, + {"t":7.31562, "x":7.50069, "y":4.11524, "heading":-0.00343, "vx":-0.02234, "vy":-0.83006, "omega":0.01361, "ax":0.32949, "ay":2.97454, "alpha":-0.00457, "fx":[4.10442,4.18406,4.09319,4.09307], "fy":[37.18082,37.18281,37.18262,37.18091]}, + {"t":7.32589, "x":7.50047, "y":4.10687, "heading":-0.00329, "vx":-0.01896, "vy":-0.7995, "omega":0.01356, "ax":0.29491, "ay":2.97855, "alpha":-0.00389, "fx":[3.68184,3.7313,3.66612,3.66604], "fy":[37.22957,37.2344,37.234,37.22973]}, + {"t":7.33617, "x":7.50029, "y":4.09881, "heading":-0.00315, "vx":-0.01593, "vy":-0.7689, "omega":0.01352, "ax":0.26375, "ay":2.98182, "alpha":-0.00275, "fx":[3.30434,3.31438,3.28449,3.28444], "fy":[37.26909,37.27653,37.27601,37.26932]}, + {"t":7.34644, "x":7.50014, "y":4.09107, "heading":-0.00301, "vx":-0.01322, "vy":-0.73827, "omega":0.01349, "ax":0.23551, "ay":2.9845, "alpha":-0.00222, "fx":[2.95909,2.94513,2.93559,2.93558], "fy":[37.30143,37.3111,37.31052,37.3017]}, + {"t":7.35671, "x":7.50002, "y":4.08364, "heading":-0.00287, "vx":-0.0108, "vy":-0.7076, "omega":0.01347, "ax":0.20981, "ay":2.9867, "alpha":-0.00181, "fx":[2.64445,2.6107,2.61768,2.6177], "fy":[37.32794,37.3396,37.339,37.32825]}, + {"t":7.36699, "x":7.49992, "y":4.07653, "heading":-0.00273, "vx":-0.00864, "vy":-0.67692, "omega":0.01345, "ax":0.18634, "ay":2.98851, "alpha":-0.00137, "fx":[2.35766,2.30356,2.32777,2.32782], "fy":[37.34967,37.36327,37.36265,37.35001]}, + {"t":7.37726, "x":7.49984, "y":4.06973, "heading":-0.00259, "vx":-0.00673, "vy":-0.64621, "omega":0.01344, "ax":0.16481, "ay":2.99001, "alpha":-0.00135, "fx":[2.09286,2.02811,2.05979,2.05988], "fy":[37.36744,37.38303,37.38244,37.36782]}, + {"t":7.38754, "x":7.49978, "y":4.06325, "heading":-0.00245, "vx":-0.00504, "vy":-0.6155, "omega":0.01342, "ax":0.14501, "ay":2.99126, "alpha":-0.0012, "fx":[1.85111,1.77048,1.8144,1.81453], "fy":[37.3817,37.39997,37.39921,37.38212]}, + {"t":7.39781, "x":7.49974, "y":4.05709, "heading":-0.00232, "vx":-0.00355, "vy":-0.58476, "omega":0.01341, "ax":0.12674, "ay":2.99229, "alpha":-0.00106, "fx":[1.62873,1.53178,1.58824,1.58842], "fy":[37.39319,37.41428,37.41349,37.39364]}, + {"t":7.40808, "x":7.49971, "y":4.05124, "heading":-0.00218, "vx":-0.00224, "vy":-0.55402, "omega":0.0134, "ax":0.10982, "ay":2.99315, "alpha":-0.00098, "fx":[1.42354,1.30969,1.37882,1.37905], "fy":[37.40221,37.42668,37.42584,37.4027]}, + {"t":7.41836, "x":7.49969, "y":4.0457, "heading":-0.00204, "vx":-0.00112, "vy":-0.52327, "omega":0.01339, "ax":0.09411, "ay":2.99386, "alpha":-0.0011, "fx":[1.23342,1.10443,1.18378,1.18405], "fy":[37.40904,37.43759,37.4367,37.40957]}, + {"t":7.42863, "x":7.49968, "y":4.04048, "heading":-0.0019, "vx":-0.00015, "vy":-0.49251, "omega":0.01338, "ax":0.07949, "ay":2.99444, "alpha":-0.00144, "fx":[1.05702,0.91436,1.00149,1.00182], "fy":[37.41386,37.44742,37.44649,37.41443]}, + {"t":7.43891, "x":7.49969, "y":4.03558, "heading":-0.00177, "vx":0.00067, "vy":-0.46174, "omega":0.01336, "ax":0.06585, "ay":2.99493, "alpha":-0.00206, "fx":[0.89327,0.73811,0.83046,0.83086], "fy":[37.41673,37.45659,37.45564,37.41736]}, + {"t":7.44918, "x":7.4997, "y":4.031, "heading":-0.00163, "vx":0.00134, "vy":-0.43097, "omega":0.01334, "ax":0.0531, "ay":2.99532, "alpha":-0.00306, "fx":[0.74133,0.57462,0.66929,0.66976], "fy":[37.4176,37.46558,37.4646,37.41829]}, + {"t":7.45945, "x":7.49971, "y":4.02673, "heading":-0.00149, "vx":0.00189, "vy":-0.4002, "omega":0.01331, "ax":0.04115, "ay":2.99564, "alpha":-0.00454, "fx":[0.60064,0.4231,0.51658,0.51713], "fy":[37.41623,37.47493,37.47395,37.417]}, + {"t":7.46973, "x":7.49974, "y":4.02277, "heading":-0.00135, "vx":0.00231, "vy":-0.36942, "omega":0.01326, "ax":0.02993, "ay":2.9959, "alpha":-0.00671, "fx":[0.47089,0.28307,0.37088,0.37154], "fy":[37.41223,37.48533,37.48435,37.41309]}, + {"t":7.48, "x":7.49976, "y":4.01914, "heading":-0.00122, "vx":0.00262, "vy":-0.33864, "omega":0.01319, "ax":0.01937, "ay":2.9961, "alpha":-0.00981, "fx":[0.35215,0.1544,0.23063,0.23142], "fy":[37.40493,37.49766,37.4967,37.40592]}, + {"t":7.49028, "x":7.49979, "y":4.01582, "heading":-0.00108, "vx":0.00282, "vy":-0.30786, "omega":0.01309, "ax":0.00942, "ay":2.99626, "alpha":-0.0152, "fx":[0.23933,0.05425,0.08835,0.08931], "fy":[37.39342,37.51283,37.51231,37.39457]}, + {"t":7.50055, "x":7.49982, "y":4.01281, "heading":-0.00095, "vx":0.00292, "vy":-0.27708, "omega":0.01294, "ax":0.00004, "ay":2.99638, "alpha":-0.02203, "fx":[0.14469,-0.04573,-0.0492,-0.04799], "fy":[37.37522,37.53382,37.53346,37.37659]}, + {"t":7.51082, "x":7.49985, "y":4.01012, "heading":-0.00082, "vx":0.00292, "vy":-0.24629, "omega":0.01271, "ax":-0.00884, "ay":2.99647, "alpha":-0.02818, "fx":[0.08818,-0.19639,-0.16775,-0.16614], "fy":[37.34784,37.56325,37.56272,37.34957]}, + {"t":7.5211, "x":7.49988, "y":4.00775, "heading":-0.00068, "vx":0.00283, "vy":-0.21551, "omega":0.01242, "ax":-0.01725, "ay":2.99652, "alpha":-0.04183, "fx":[0.02762,-0.26474,-0.3137,-0.31156], "fy":[37.30972,37.60239,37.60223,37.3119]}, + {"t":7.53137, "x":7.49991, "y":4.00569, "heading":-0.00056, "vx":0.00265, "vy":-0.18472, "omega":0.01199, "ax":-0.02522, "ay":2.99656, "alpha":-0.06118, "fx":[-0.01004,-0.31012,-0.47179,-0.46892], "fy":[37.25565,37.6567,37.65704,37.25845]}, + {"t":7.54165, "x":7.49993, "y":4.00395, "heading":-0.00043, "vx":0.00239, "vy":-0.15393, "omega":0.01136, "ax":-0.03278, "ay":2.99657, "alpha":-0.09107, "fx":[-0.02911,-0.28763,-0.66319,-0.65931], "fy":[37.17827,37.73349,37.73474,37.18191]}, + {"t":7.55192, "x":7.49995, "y":4.00253, "heading":-0.00032, "vx":0.00205, "vy":-0.12315, "omega":0.01043, "ax":-0.03998, "ay":2.99656, "alpha":-0.13145, "fx":[0.00897,-0.26071,-0.87624,-0.87099], "fy":[37.06567,37.84482,37.84705,37.0705]}, + {"t":7.56219, "x":7.49997, "y":4.00142, "heading":-0.00021, "vx":0.00164, "vy":-0.09236, "omega":0.00908, "ax":-0.04683, "ay":2.99654, "alpha":-0.1915, "fx":[0.10261,-0.15332,-1.14881,-1.14187], "fy":[36.90217,38.00586,38.01011,36.90877]}, + {"t":7.57247, "x":7.49999, "y":4.00063, "heading":-0.00012, "vx":0.00116, "vy":-0.06157, "omega":0.00711, "ax":-0.05335, "ay":2.9965, "alpha":-0.27796, "fx":[0.29276,0.02271,-1.49598,-1.48718], "fy":[36.66347,38.24138,38.24775,36.67249]}, + {"t":7.58274, "x":7.5, "y":4.00016, "heading":-0.00004, "vx":0.00061, "vy":-0.03079, "omega":0.00425, "ax":-0.05958, "ay":2.99645, "alpha":-0.41403, "fx":[0.61,0.59285,-1.95559,-2.22638], "fy":[36.59543,38.50483,38.51905,36.20338]}, + {"t":7.59302, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/deploy/choreo/CurveRotateTest.traj b/deploy/choreo/CurveRotateTest.traj new file mode 100644 index 00000000..4c74224f --- /dev/null +++ b/deploy/choreo/CurveRotateTest.traj @@ -0,0 +1,279 @@ +{ + "name":"CurveRotateTest", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.5, "y":4.0, "heading":0.0, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.84660005569458, "y":4.7060933113098145, "heading":0.0, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":9.639573097229004, "y":3.2634711265563965, "heading":0.0, "intervals":51, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":10.0, "y":4.0, "heading":3.141592653589793, "intervals":51, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":9.639573097229004, "y":3.2634711265563965, "heading":0.0, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":7.84660005569458, "y":4.7060933113098145, "heading":0.0, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":7.5, "y":4.0, "heading":0.0, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":1.3}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":3.0}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":3.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.84660005569458 m", "val":7.84660005569458}, "y":{"exp":"4.7060933113098145 m", "val":4.7060933113098145}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"9.639573097229004 m", "val":9.639573097229004}, "y":{"exp":"3.2634711265563965 m", "val":3.2634711265563965}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":51, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x + 2.5 m", "val":10.0}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":51, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"9.639573097229004 m", "val":9.639573097229004}, "y":{"exp":"3.2634711265563965 m", "val":3.2634711265563965}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"7.84660005569458 m", "val":7.84660005569458}, "y":{"exp":"4.7060933113098145 m", "val":4.7060933113098145}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":21, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"MaxVelocity", "val":1.3}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":{"exp":"MaxAcceleration", "val":3.0}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"3 rad / s", "val":3.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.8928,2.87714,3.79598,4.71483,6.69917,7.59196], + "samples":[ + {"t":0.0, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-0.05916, "ay":2.99733, "alpha":4.828, "fx":[-14.84326,-16.04274,14.61329,13.31478], "fy":[50.80309,24.08904,24.22041,50.75414]}, + {"t":0.02976, "x":7.49997, "y":4.00133, "heading":0.0, "vx":-0.00176, "vy":0.0892, "omega":0.14368, "ax":-0.03884, "ay":2.99863, "alpha":3.96554, "fx":[-12.20148,-12.9782,12.06804,11.16968], "fy":[48.42192,26.55298,26.59971,48.35695]}, + {"t":0.05952, "x":7.4999, "y":4.00531, "heading":0.00428, "vx":-0.00292, "vy":0.17844, "omega":0.2617, "ax":-0.01532, "ay":2.99876, "alpha":3.26035, "fx":[-9.92759,-10.33588,10.10427,9.39343], "fy":[46.45814,28.43144,28.58094,46.4673]}, + {"t":0.08928, "x":7.49981, "y":4.01195, "heading":0.01206, "vx":-0.00337, "vy":0.26768, "omega":0.35872, "ax":0.0122, "ay":2.99867, "alpha":2.67229, "fx":[-7.92978,-8.03427,8.60599,7.96796], "fy":[44.79985,29.97386,30.25211,44.9076]}, + {"t":0.11904, "x":7.49972, "y":4.02124, "heading":0.02274, "vx":-0.00301, "vy":0.35692, "omega":0.43825, "ax":0.0448, "ay":2.99824, "alpha":2.18368, "fx":[-6.13987,-6.009,7.50396,6.88494], "fy":[43.40806,31.24323,31.64797,43.61263]}, + {"t":0.1488, "x":7.49965, "y":4.03319, "heading":0.03578, "vx":-0.00168, "vy":0.44615, "omega":0.50324, "ax":0.08403, "ay":2.99725, "alpha":1.7805, "fx":[-4.49322,-4.19152,6.75324,6.13305], "fy":[42.25367,32.2774,32.79356,42.53785]}, + {"t":0.17856, "x":7.49963, "y":4.0478, "heading":0.05076, "vx":0.00082, "vy":0.53535, "omega":0.55623, "ax":0.13211, "ay":2.99534, "alpha":1.44792, "fx":[-2.92571,-2.5084,6.33078,5.70886], "fy":[41.29057,33.12103,33.72425,41.63102]}, + {"t":0.20832, "x":7.49972, "y":4.06506, "heading":0.06731, "vx":0.00476, "vy":0.62449, "omega":0.59932, "ax":0.19236, "ay":2.99185, "alpha":1.17485, "fx":[-1.36473,-0.87753,6.23787,5.62227], "fy":[40.48243,33.78831,34.46618,40.85558]}, + {"t":0.23808, "x":7.49994, "y":4.08496, "heading":0.08515, "vx":0.01048, "vy":0.71353, "omega":0.63428, "ax":0.26995, "ay":2.98556, "alpha":0.95298, "fx":[0.2794,0.80135,6.50815,5.90841], "fy":[39.79524,34.28122,35.02175,40.17995]}, + {"t":0.26784, "x":7.50037, "y":4.10752, "heading":0.10402, "vx":0.01851, "vy":0.80238, "omega":0.66264, "ax":0.37336, "ay":2.97402, "alpha":0.7713, "fx":[2.13264,2.66353,7.22298,6.64896], "fy":[39.15838,34.61828,35.38774,39.53652]}, + {"t":0.2976, "x":7.50109, "y":4.13272, "heading":0.12374, "vx":0.02963, "vy":0.89089, "omega":0.68559, "ax":0.5174, "ay":2.95184, "alpha":0.62634, "fx":[4.39737,4.92063,8.54644,8.00559], "fy":[38.50191,34.69657,35.5319,38.86138]}, + {"t":0.32736, "x":7.5022, "y":4.16054, "heading":0.14415, "vx":0.04502, "vy":0.97873, "omega":0.70423, "ax":0.72978, "ay":2.90583, "alpha":0.51261, "fx":[7.43245,7.94081,10.80993,10.30586], "fy":[37.64451,34.36848,35.30248,37.976]}, + {"t":0.35712, "x":7.50386, "y":4.19095, "heading":0.16511, "vx":0.06674, "vy":1.06521, "omega":0.71949, "ax":1.06625, "ay":2.79863, "alpha":0.4236, "fx":[11.94512,12.43899,14.69807,14.23043], "fy":[36.09385,33.21355,34.23025,36.39373]}, + {"t":0.38688, "x":7.50632, "y":4.22389, "heading":0.18652, "vx":0.09847, "vy":1.1485, "omega":0.7321, "ax":1.63811, "ay":2.50476, "alpha":0.35019, "fx":[19.34229,19.8121,21.59103,21.16004], "fy":[32.24105,29.75856,30.72482,32.51361]}, + {"t":0.41664, "x":7.50998, "y":4.25918, "heading":0.2083, "vx":0.14722, "vy":1.22304, "omega":0.74252, "ax":2.53222, "ay":1.58982, "alpha":0.28784, "fx":[30.7442,31.12328,32.5551,32.18852], "fy":[20.62551,18.58928,19.37102,20.90528]}, + {"t":0.4464, "x":7.51548, "y":4.29628, "heading":0.2304, "vx":0.22258, "vy":1.27035, "omega":0.75108, "ax":2.97446, "ay":-0.29628, "alpha":0.18508, "fx":[36.43887,36.71978,37.92122,37.64307], "fy":[-3.38934,-3.97746,-4.37684,-3.07038]}, + {"t":0.47616, "x":7.52342, "y":4.33396, "heading":0.25275, "vx":0.3111, "vy":1.26153, "omega":0.75659, "ax":2.87876, "ay":-0.81258, "alpha":0.18209, "fx":[35.34546,35.59913,36.6187,36.37469], "fy":[-9.79869,-10.75393,-10.593,-9.48339]}, + {"t":0.50592, "x":7.53396, "y":4.37114, "heading":0.27527, "vx":0.39677, "vy":1.23735, "omega":0.76201, "ax":2.8164, "ay":-1.01263, "alpha":0.15143, "fx":[34.64031,34.88366,35.76074,35.53517], "fy":[-12.39777,-13.08746,-13.05436,-12.09177]}, + {"t":0.53568, "x":7.54701, "y":4.40751, "heading":0.29795, "vx":0.48059, "vy":1.20722, "omega":0.76652, "ax":2.73998, "ay":-1.20734, "alpha":0.11683, "fx":[33.7386,33.98295,34.7448,34.53245], "fy":[-14.9572,-15.24051,-15.50884,-14.66024]}, + {"t":0.56544, "x":7.56253, "y":4.44291, "heading":0.32076, "vx":0.56213, "vy":1.17129, "omega":0.76999, "ax":2.61483, "ay":-1.46071, "alpha":0.09647, "fx":[32.21574,32.45459,33.13767,32.93371], "fy":[-18.19499,-18.27986,-18.6577,-17.90281]}, + {"t":0.5952, "x":7.58041, "y":4.47712, "heading":0.34367, "vx":0.63995, "vy":1.12782, "omega":0.77286, "ax":2.31651, "ay":-1.89993, "alpha":0.09433, "fx":[28.518,28.75031,29.37889,29.17806], "fy":[-23.6774,-23.8556,-24.07101,-23.39227]}, + {"t":0.62496, "x":7.60049, "y":4.50984, "heading":0.36667, "vx":0.70889, "vy":1.07127, "omega":0.77567, "ax":2.01509, "ay":-2.21796, "alpha":0.0923, "fx":[24.77115,25.00593,25.59007,25.38721], "fy":[-27.64939,-27.88764,-27.9909,-27.37013]}, + {"t":0.65472, "x":7.62247, "y":4.54074, "heading":0.38976, "vx":0.76886, "vy":1.00527, "omega":0.77842, "ax":1.76995, "ay":-2.41874, "alpha":0.0866, "fx":[21.72,21.96172,22.51235,22.30365], "fy":[-30.17716,-30.379,-30.4803,-29.90048]}, + {"t":0.68448, "x":7.64614, "y":4.56958, "heading":0.41292, "vx":0.82153, "vy":0.93329, "omega":0.781, "ax":1.57752, "ay":-2.54889, "alpha":0.08603, "fx":[19.32267,19.56802,20.10139,19.88371], "fy":[-31.80485,-32.03452,-32.078,-31.52736]}, + {"t":0.71424, "x":7.67129, "y":4.59623, "heading":0.43617, "vx":0.86848, "vy":0.85743, "omega":0.78356, "ax":1.42608, "ay":-2.63696, "alpha":0.08656, "fx":[17.43059,17.68394,18.20976,17.97951], "fy":[-32.90748,-33.15833,-33.15788,-32.62448]}, + {"t":0.744, "x":7.69776, "y":4.62058, "heading":0.45949, "vx":0.91092, "vy":0.77895, "omega":0.78613, "ax":1.30529, "ay":-2.69906, "alpha":0.08784, "fx":[15.91291,16.18149,16.70882,16.46121], "fy":[-33.68904,-33.94701,-33.92266,-33.39454]}, + {"t":0.77376, "x":7.72545, "y":4.64257, "heading":0.48288, "vx":0.94976, "vy":0.69863, "omega":0.78875, "ax":1.20739, "ay":-2.74447, "alpha":0.09224, "fx":[14.67229,14.96164,15.50354,15.23226], "fy":[-34.25671,-34.54485,-34.47807,-33.94375]}, + {"t":0.80352, "x":7.75425, "y":4.66214, "heading":0.50635, "vx":0.9857, "vy":0.61695, "omega":0.79149, "ax":1.1268, "ay":-2.7787, "alpha":0.09947, "fx":[13.63694,13.95545,14.5254,14.22226], "fy":[-34.68241,-35.01458,-34.89572,-34.3424]}, + {"t":0.83328, "x":7.78408, "y":4.67927, "heading":0.52991, "vx":1.01923, "vy":0.53426, "omega":0.79445, "ax":1.05949, "ay":-2.8052, "alpha":0.1094, "fx":[12.75428,13.11359,13.72607,13.38045], "fy":[-35.01185,-35.39378,-35.22043,-34.63398]}, + {"t":0.86304, "x":7.81489, "y":4.69393, "heading":0.55355, "vx":1.05076, "vy":0.45078, "omega":0.79771, "ax":1.00254, "ay":-2.82617, "alpha":0.12304, "fx":[11.98553,12.39949,13.07178,12.67015], "fy":[-35.27118,-35.71803,-35.47745,-34.84201]}, + {"t":0.8928, "x":7.8466, "y":4.70609, "heading":0.57729, "vx":1.0806, "vy":0.36667, "omega":0.80137, "ax":0.94665, "ay":-2.84456, "alpha":0.96861, "fx":[7.7216,10.90586,15.90231,12.80292], "fy":[-35.00309,-39.16641,-36.28745,-31.77099]}, + {"t":0.93024, "x":7.88772, "y":4.71783, "heading":0.60729, "vx":1.11604, "vy":0.26017, "omega":0.83763, "ax":0.87334, "ay":-2.86886, "alpha":0.74023, "fx":[7.75579,10.30164,14.0542,11.55535], "fy":[-35.51575,-38.63761,-36.32636,-32.96333]}, + {"t":0.96768, "x":7.93012, "y":4.72556, "heading":0.63866, "vx":1.14874, "vy":0.15276, "omega":0.86535, "ax":0.77872, "ay":-2.89581, "alpha":0.5624, "fx":[7.301,9.34593,12.15265,10.13657], "fy":[-36.01116,-38.28137,-36.50572,-33.99237]}, + {"t":1.00512, "x":7.97367, "y":4.72925, "heading":0.67106, "vx":1.17789, "vy":0.04434, "omega":0.8864, "ax":0.65324, "ay":-2.92646, "alpha":0.42626, "fx":[6.29307,7.9366,10.02805,8.40416], "fy":[-36.50757,-38.12349,-36.78952,-34.90259]}, + {"t":1.04256, "x":8.01823, "y":4.72886, "heading":0.70424, "vx":1.20235, "vy":-0.06523, "omega":0.90236, "ax":0.48016, "ay":-2.95951, "alpha":0.32223, "fx":[4.5598,5.88213,7.43784,6.12847], "fy":[-36.99566,-38.1184,-37.13931,-35.72211]}, + {"t":1.08, "x":8.06359, "y":4.72434, "heading":0.73803, "vx":1.22033, "vy":-0.17604, "omega":0.91443, "ax":0.22982, "ay":-2.989, "alpha":0.2433, "fx":[1.7589,2.82541,3.98327,2.92349], "fy":[-37.41352,-38.16549,-37.47144,-36.39963]}, + {"t":1.11744, "x":8.10944, "y":4.71565, "heading":0.77226, "vx":1.22893, "vy":-0.28794, "omega":0.92354, "ax":-0.15177, "ay":-2.99342, "alpha":0.18239, "fx":[-2.76071,-1.89834,-1.03284,-1.8967], "fy":[-37.50573,-37.95839,-37.51438,-36.69261]}, + {"t":1.15488, "x":8.15534, "y":4.70278, "heading":0.80684, "vx":1.22325, "vy":-0.40002, "omega":0.93037, "ax":-0.74825, "ay":-2.90153, "alpha":0.13248, "fx":[-10.02426,-9.3285,-8.67504,-9.38471], "fy":[-36.39785,-36.56151,-36.37978,-35.73747]}, + {"t":1.19232, "x":8.20062, "y":4.68576, "heading":0.84167, "vx":1.19524, "vy":-0.50865, "omega":0.93533, "ax":-1.27797, "ay":-2.70905, "alpha":0.0983, "fx":[-16.49659,-15.93787,-15.44008,-16.02373], "fy":[-34.00749,-34.01319,-33.97116,-33.46074]}, + {"t":1.22976, "x":8.24447, "y":4.66482, "heading":0.87669, "vx":1.14739, "vy":-0.61008, "omega":0.93901, "ax":-1.51681, "ay":-2.581, "alpha":0.07966, "fx":[-19.36707,-18.92343,-18.53569,-19.01408], "fy":[-32.38835,-32.39765,-32.33466,-31.92944]}, + {"t":1.2672, "x":8.28637, "y":4.64017, "heading":0.91185, "vx":1.0906, "vy":-0.70672, "omega":0.94199, "ax":-1.73236, "ay":-2.43819, "alpha":0.06356, "fx":[-21.97479,-21.61429,-21.31917,-21.70969], "fy":[-30.59326,-30.58275,-30.52594,-30.20742]}, + {"t":1.30464, "x":8.32598, "y":4.612, "heading":0.94712, "vx":1.02574, "vy":-0.798, "omega":0.94437, "ax":-1.9326, "ay":-2.27608, "alpha":0.04216, "fx":[-24.40877,-24.11919,-23.8924,-24.20956], "fy":[-28.5923,-28.4263,-28.51653,-28.26868]}, + {"t":1.34209, "x":8.36303, "y":4.58053, "heading":0.98248, "vx":0.95338, "vy":-0.88322, "omega":0.94595, "ax":-2.11306, "ay":-2.094, "alpha":0.05992, "fx":[-26.61042,-26.37077,-26.2094,-26.46243], "fy":[-26.18652,-26.4869,-26.10761,-25.91919]}, + {"t":1.37953, "x":8.39725, "y":4.54599, "heading":1.01789, "vx":0.87427, "vy":-0.96162, "omega":0.94819, "ax":-2.25993, "ay":-1.88631, "alpha":0.0466, "fx":[-28.40222,-28.21633,-28.08723,-28.29049], "fy":[-23.60075,-23.81405,-23.52162,-23.37932]}, + {"t":1.41697, "x":8.4284, "y":4.50867, "heading":1.05339, "vx":0.78966, "vy":-1.03224, "omega":0.94994, "ax":-2.28279, "ay":-1.60523, "alpha":0.11111, "fx":[-28.65109,-28.50397,-28.41445,-28.56996], "fy":[-19.76751,-21.20827,-19.69354,-19.59225]}, + {"t":1.45441, "x":8.45636, "y":4.4689, "heading":1.08896, "vx":0.70419, "vy":-1.09234, "omega":0.9541, "ax":-1.0991, "ay":-0.67994, "alpha":0.0227, "fx":[-13.83062,-13.70847,-13.64638,-13.7693], "fy":[-8.54537,-8.57017,-8.47716,-8.40438]}, + {"t":1.49185, "x":8.48196, "y":4.42752, "heading":1.12468, "vx":0.66304, "vy":-1.1178, "omega":0.95495, "ax":-0.06906, "ay":-0.04086, "alpha":-0.0459, "fx":[-0.93193,-0.83805,-0.79464,-0.88845], "fy":[-0.82234,0.2593,-0.76496,-0.71487]}, + {"t":1.52929, "x":8.50673, "y":4.38564, "heading":1.16043, "vx":0.66045, "vy":-1.11933, "omega":0.95323, "ax":-0.03183, "ay":-0.01876, "alpha":-0.0068, "fx":[-0.4433,-0.37935,-0.35239,-0.41634], "fy":[-0.34417,-0.02539,-0.30014,-0.26814]}, + {"t":1.56673, "x":8.53144, "y":4.34372, "heading":1.19612, "vx":0.65926, "vy":-1.12003, "omega":0.95297, "ax":0.00926, "ay":0.00545, "alpha":-0.00233, "fx":[0.0857,0.12934,0.14589,0.10225], "fy":[0.00166,0.18229,0.03445,0.05432]}, + {"t":1.60417, "x":8.55613, "y":4.30179, "heading":1.2318, "vx":0.65961, "vy":-1.11983, "omega":0.95289, "ax":-0.0015, "ay":-0.00088, "alpha":0.00449, "fx":[-0.03782,-0.00926,0.00034,-0.02821], "fy":[-0.02876,-0.01667,-0.00525,0.00654]}, + {"t":1.64161, "x":8.58082, "y":4.25986, "heading":1.26748, "vx":0.65955, "vy":-1.11986, "omega":0.95305, "ax":0.00036, "ay":0.00021, "alpha":0.0039, "fx":[-0.00742,0.01093,0.01631,-0.00205], "fy":[-0.00469,-0.01486,0.01167,0.01835]}, + {"t":1.67905, "x":8.60551, "y":4.21793, "heading":1.30316, "vx":0.65956, "vy":-1.11985, "omega":0.9532, "ax":-0.00043, "ay":-0.00025, "alpha":0.00337, "fx":[-0.01244,-0.00101,0.00181,-0.00962], "fy":[-0.00352,-0.02737,0.00743,0.01093]}, + {"t":1.71649, "x":8.63021, "y":4.17601, "heading":1.33885, "vx":0.65955, "vy":-1.11986, "omega":0.95333, "ax":0.00001, "ay":0.0, "alpha":0.0023, "fx":[-0.00404,0.00289,0.00424,-0.00268], "fy":[0.00114,-0.01867,0.00808,0.0097]}, + {"t":1.75393, "x":8.6549, "y":4.13408, "heading":1.37454, "vx":0.65955, "vy":-1.11986, "omega":0.95341, "ax":0.00001, "ay":0.00001, "alpha":0.00147, "fx":[-0.00215,0.0019,0.00244,-0.00162], "fy":[0.00164,-0.01322,0.00569,0.00622]}, + {"t":1.79137, "x":8.6796, "y":4.09215, "heading":1.41024, "vx":0.65955, "vy":-1.11986, "omega":0.95347, "ax":0.00005, "ay":0.00003, "alpha":0.00081, "fx":[-0.00055,0.00167,0.00176,-0.00045], "fy":[0.00174,-0.00756,0.00366,0.00359]}, + {"t":1.82881, "x":8.70429, "y":4.05022, "heading":1.44594, "vx":0.65955, "vy":-1.11986, "omega":0.9535, "ax":0.00002, "ay":0.00001, "alpha":0.0003, "fx":[-0.00015,0.00083,0.00068,-0.0003], "fy":[0.00123,-0.00322,0.0015,0.00112]}, + {"t":1.86625, "x":8.72898, "y":4.00829, "heading":1.48164, "vx":0.65955, "vy":-1.11986, "omega":0.95351, "ax":0.0, "ay":0.0, "alpha":-0.00014, "fx":[0.00011,0.00008,-0.0002,-0.00017], "fy":[0.00069,0.00075,-0.00051,-0.00104]}, + {"t":1.90369, "x":8.75368, "y":3.96637, "heading":1.51734, "vx":0.65955, "vy":-1.11986, "omega":0.9535, "ax":-0.00003, "ay":-0.00002, "alpha":-0.00057, "fx":[0.00034,-0.00075,-0.00109,0.00001], "fy":[0.00015,0.00476,-0.00262,-0.00317]}, + {"t":1.94113, "x":8.77837, "y":3.92444, "heading":1.55304, "vx":0.65955, "vy":-1.11986, "omega":0.95348, "ax":-0.00006, "ay":-0.00003, "alpha":-0.00107, "fx":[0.00071,-0.00181,-0.00214,0.00039], "fy":[-0.00031,0.00928,-0.00509,-0.00556]}, + {"t":1.97857, "x":8.80307, "y":3.88251, "heading":1.58874, "vx":0.65955, "vy":-1.11986, "omega":0.95344, "ax":-0.00003, "ay":-0.00002, "alpha":-0.00171, "fx":[0.00199,-0.00262,-0.00283,0.00179], "fy":[-0.00019,0.01506,-0.0078,-0.00805]}, + {"t":2.01601, "x":8.82776, "y":3.84058, "heading":1.62443, "vx":0.65955, "vy":-1.11986, "omega":0.95338, "ax":-0.00001, "ay":-0.00001, "alpha":-0.0025, "fx":[0.00365,-0.00411,-0.00399,0.00377], "fy":[0.00066,0.02098,-0.01113,-0.01091]}, + {"t":2.05345, "x":8.85245, "y":3.79865, "heading":1.66013, "vx":0.65955, "vy":-1.11987, "omega":0.95328, "ax":0.00034, "ay":0.0002, "alpha":-0.00351, "fx":[0.01002,-0.00241,-0.00161,0.01082], "fy":[0.00517,0.02919,-0.01277,-0.01168]}, + {"t":2.09089, "x":8.87715, "y":3.75673, "heading":1.69582, "vx":0.65956, "vy":-1.11986, "omega":0.95315, "ax":-0.00013, "ay":-0.00007, "alpha":-0.0043, "fx":[0.00699,-0.01225,-0.01016,0.00909], "fy":[0.00911,0.0203,-0.01788,-0.01525]}, + {"t":2.12833, "x":8.90184, "y":3.7148, "heading":1.7315, "vx":0.65955, "vy":-1.11986, "omega":0.95299, "ax":0.00104, "ay":0.00061, "alpha":-0.00525, "fx":[0.0253,-0.00357,0.00077,0.02963], "fy":[0.02975,0.01625,-0.01024,-0.00506]}, + {"t":2.16577, "x":8.92653, "y":3.67287, "heading":1.76719, "vx":0.65959, "vy":-1.11984, "omega":0.9528, "ax":-0.00666, "ay":-0.00392, "alpha":-0.00267, "fx":[-0.06612,-0.10857,-0.1005,-0.05805], "fy":[0.01984,-0.14805,-0.03864,-0.02938]}, + {"t":2.20321, "x":8.95123, "y":3.63094, "heading":1.80286, "vx":0.65934, "vy":-1.11998, "omega":0.9527, "ax":0.02194, "ay":0.01293, "alpha":-0.00123, "fx":[0.29758,0.23708,0.25097,0.31147], "fy":[0.28288,-0.04996,0.19897,0.21451]}, + {"t":2.24065, "x":8.97593, "y":3.58902, "heading":1.83853, "vx":0.66016, "vy":-1.1195, "omega":0.95265, "ax":0.06147, "ay":0.03634, "alpha":0.01447, "fx":[0.79961,0.71412,0.73726,0.82268], "fy":[0.76595,-0.26877,0.64738,0.67225]}, + {"t":2.27809, "x":9.00069, "y":3.54713, "heading":1.8742, "vx":0.66247, "vy":-1.11814, "omega":0.95319, "ax":0.93622, "ay":0.57491, "alpha":-0.0143, "fx":[11.74122,11.62881,11.664,11.77675], "fy":[7.32811,7.04481,7.1678,7.20484]}, + {"t":2.31553, "x":9.02615, "y":3.50567, "heading":1.90988, "vx":0.69752, "vy":-1.09662, "omega":0.95266, "ax":2.26241, "ay":1.56855, "alpha":-0.06421, "fx":[28.3235,28.18666,28.2338,28.37636], "fy":[19.35671,20.72158,19.14892,19.20029]}, + {"t":2.35297, "x":9.05385, "y":3.46571, "heading":1.94555, "vx":0.78222, "vy":-1.03789, "omega":0.95025, "ax":2.26955, "ay":1.86656, "alpha":-0.03684, "fx":[28.41758,28.25155,28.31222,28.49626], "fy":[23.44613,23.46443,23.17287,23.24467]}, + {"t":2.39042, "x":9.08472, "y":3.42816, "heading":1.98113, "vx":0.8672, "vy":-0.968, "omega":0.94887, "ax":2.12732, "ay":2.07734, "alpha":-0.04932, "fx":[26.64928,26.42749,26.52866,26.76061], "fy":[26.09149,26.19408,25.74167,25.83963]}, + {"t":2.42786, "x":9.11868, "y":3.39337, "heading":2.01665, "vx":0.94684, "vy":-0.89023, "omega":0.94703, "ax":1.94895, "ay":2.26125, "alpha":-0.05078, "fx":[24.42543,24.15424,24.28654,24.5815], "fy":[28.56571,28.13074,28.11595,28.25021]}, + {"t":2.4653, "x":9.1555, "y":3.36163, "heading":2.05211, "vx":1.01981, "vy":-0.80556, "omega":0.94512, "ax":1.75019, "ay":2.42503, "alpha":-0.06695, "fx":[21.95042,21.6014,21.7914,22.16603], "fy":[30.68513,30.16591,30.10848,30.29189]}, + {"t":2.50274, "x":9.19491, "y":3.33317, "heading":2.0875, "vx":1.08534, "vy":-0.71477, "omega":0.94262, "ax":1.53592, "ay":2.56946, "alpha":-0.08867, "fx":[19.28223,18.83511,19.10088,19.57778], "fy":[32.56957,31.99425,31.82921,32.07994]}, + {"t":2.54018, "x":9.23662, "y":3.30821, "heading":2.12279, "vx":1.14285, "vy":-0.61857, "omega":0.9393, "ax":1.30618, "ay":2.69543, "alpha":-0.11607, "fx":[16.42488,15.83949,16.21696,16.82781], "fy":[34.2708,33.52214,33.31738,33.66128]}, + {"t":2.57762, "x":9.28032, "y":3.28693, "heading":2.15796, "vx":1.19175, "vy":-0.51765, "omega":0.93495, "ax":0.95413, "ay":2.84038, "alpha":-0.15333, "fx":[12.0452,11.26851,11.8014,12.5913], "fy":[36.24007,35.2901,35.00633,35.48273]}, + {"t":2.61506, "x":9.32561, "y":3.26954, "heading":2.19296, "vx":1.22747, "vy":-0.41131, "omega":0.92921, "ax":0.33246, "ay":2.97867, "alpha":-0.20529, "fx":[4.29807,3.27627,4.01187,5.03664], "fy":[38.1201,37.13477,36.50674,37.17196]}, + {"t":2.6525, "x":9.3718, "y":3.25623, "heading":2.22775, "vx":1.23992, "vy":-0.29978, "omega":0.92153, "ax":-0.0951, "ay":2.99624, "alpha":-0.27211, "fx":[-1.02589,-2.35648,-1.35025,-0.02252], "fy":[38.58285,37.38837,36.45604,37.38458]}, + {"t":2.68994, "x":9.41816, "y":3.24711, "heading":2.26225, "vx":1.23636, "vy":-0.1876, "omega":0.91134, "ax":-0.37747, "ay":2.97429, "alpha":-0.36009, "fx":[-4.54305,-6.26378,-4.89158,-3.17509], "fy":[38.64031,37.1296,35.82679,37.11795]}, + {"t":2.72738, "x":9.46418, "y":3.24217, "heading":2.29638, "vx":1.22223, "vy":-0.07625, "omega":0.89786, "ax":-0.57211, "ay":2.94335, "alpha":-0.47554, "fx":[-6.97752,-9.19221,-7.32381,-5.11172], "fy":[38.69822,36.72784,34.97853,36.76314]}, + {"t":2.76482, "x":9.50954, "y":3.24138, "heading":2.32999, "vx":1.20081, "vy":0.03396, "omega":0.88005, "ax":-0.71252, "ay":2.91277, "alpha":-0.6262, "fx":[-8.75696,-11.59468,-9.0572,-6.21733], "fy":[38.89654,36.30249,33.99705,36.44253]}, + {"t":2.80226, "x":9.554, "y":3.24469, "heading":2.36294, "vx":1.17413, "vy":0.14301, "omega":0.85661, "ax":-0.81786, "ay":2.88514, "alpha":-0.82326, "fx":[-10.13212,-13.75332,-10.31971,-6.68806], "fy":[39.31238,35.86603,32.86669,36.21176]}, + {"t":2.8397, "x":9.59739, "y":3.25207, "heading":2.39501, "vx":1.14351, "vy":0.25103, "omega":0.82578, "ax":-0.89947, "ay":2.86088, "alpha":-1.07848, "fx":[-11.26163,-15.86352,-11.23667,-6.61163], "fy":[39.98783,35.41178,31.55308,36.09147]}, + {"t":2.87714, "x":9.63957, "y":3.26347, "heading":2.42593, "vx":1.10983, "vy":0.35814, "omega":0.7854, "ax":-0.95991, "ay":2.83952, "alpha":0.0006, "fx":[-11.99704,-11.9984,-11.99279,-12.00703], "fy":[35.55327,35.28869,35.57379,35.56025]}, + {"t":2.90678, "x":9.67205, "y":3.27533, "heading":2.44921, "vx":1.08138, "vy":0.44231, "omega":0.78542, "ax":-1.02238, "ay":2.8189, "alpha":-0.00281, "fx":[-12.77939,-12.79124,-12.77478,-12.77335], "fy":[35.28507,35.11005,35.27265,35.27711]}, + {"t":2.93642, "x":9.70365, "y":3.28968, "heading":2.47249, "vx":1.05108, "vy":0.52586, "omega":0.78534, "ax":-1.09597, "ay":2.79096, "alpha":-0.00589, "fx":[-13.69954,-13.72394,-13.69369,-13.68154], "fy":[34.95046,34.74398,34.91856,34.93477]}, + {"t":2.96606, "x":9.73432, "y":3.30649, "heading":2.49577, "vx":1.01859, "vy":0.60858, "omega":0.78516, "ax":-1.18442, "ay":2.7544, "alpha":-0.00825, "fx":[-14.80539,-14.83895,-14.7979,-14.77876], "fy":[34.50545,34.26941,34.46023,34.48496]}, + {"t":2.9957, "x":9.76399, "y":3.32574, "heading":2.51904, "vx":0.98349, "vy":0.69022, "omega":0.78492, "ax":-1.29226, "ay":2.70526, "alpha":-0.01009, "fx":[-16.15345,-16.19368,-16.14431,-16.12131], "fy":[33.90228,33.63185,33.84909,33.87956]}, + {"t":3.02534, "x":9.79258, "y":3.34739, "heading":2.5423, "vx":0.94518, "vy":0.77041, "omega":0.78462, "ax":-1.42576, "ay":2.63704, "alpha":-0.01113, "fx":[-17.82245,-17.86593,-17.81197,-17.78785], "fy":[33.0549,32.76596,32.99911,33.03198]}, + {"t":3.05498, "x":9.81997, "y":3.37138, "heading":2.56556, "vx":0.90292, "vy":0.84857, "omega":0.78429, "ax":-1.59351, "ay":2.53881, "alpha":-0.0122, "fx":[-19.91845,-19.96514,-19.90731,-19.88436], "fy":[31.83858,31.50011,31.78445,31.81729]}, + {"t":3.08462, "x":9.84603, "y":3.39765, "heading":2.58881, "vx":0.85569, "vy":0.92382, "omega":0.78393, "ax":-1.80629, "ay":2.39156, "alpha":-0.01241, "fx":[-22.57785,-22.62275,-22.56696,-22.54704], "fy":[30.00293,29.63624,29.95447,29.98458]}, + {"t":3.11426, "x":9.8706, "y":3.42608, "heading":2.61204, "vx":0.80215, "vy":0.99471, "omega":0.78356, "ax":-2.07394, "ay":2.16281, "alpha":-0.01332, "fx":[-25.92208,-25.96549,-25.91243,-25.89697], "fy":[27.16284,26.7055,27.12377,27.14856]}, + {"t":3.1439, "x":9.89346, "y":3.45652, "heading":2.63527, "vx":0.74068, "vy":1.05881, "omega":0.78317, "ax":-2.38624, "ay":1.81126, "alpha":-0.01421, "fx":[-29.82491,-29.86258,-29.81754,-29.80722], "fy":[22.78976,22.23192,22.7617,22.7798]}, + {"t":3.17354, "x":9.91437, "y":3.48869, "heading":2.65848, "vx":0.66995, "vy":1.1125, "omega":0.78275, "ax":-2.60643, "ay":1.47525, "alpha":-0.01373, "fx":[-32.57501,-32.61087,-32.5705,-32.56506], "fy":[18.58571,18.02826,18.56881,18.57981]}, + {"t":3.20318, "x":9.93308, "y":3.52232, "heading":2.68168, "vx":0.5927, "vy":1.15623, "omega":0.78234, "ax":-2.70812, "ay":1.27655, "alpha":-0.01048, "fx":[-33.84553,-33.87425,-33.84388,-33.84212], "fy":[16.06461,15.645,16.05639,16.06172]}, + {"t":3.23282, "x":9.94946, "y":3.55715, "heading":2.70487, "vx":0.51243, "vy":1.19406, "omega":0.78203, "ax":-2.78805, "ay":1.08713, "alpha":-0.00509, "fx":[-34.84678,-34.86031,-34.84752,-34.84801], "fy":[13.64105,13.43787,13.63764,13.63978]}, + {"t":3.26246, "x":9.96342, "y":3.59302, "heading":2.72805, "vx":0.42979, "vy":1.22629, "omega":0.78188, "ax":-2.85404, "ay":0.89347, "alpha":-0.00344, "fx":[-35.67228,-35.6785,-35.67482,-35.67649], "fy":[11.20624,11.05777,11.20424,11.20545]}, + {"t":3.2921, "x":9.97491, "y":3.62976, "heading":2.75122, "vx":0.3452, "vy":1.25277, "omega":0.78178, "ax":-2.90607, "ay":0.69539, "alpha":-0.00731, "fx":[-36.3224,-36.32736,-36.32585,-36.32775], "fy":[8.77057,8.46354,8.76624,8.76914]}, + {"t":3.32174, "x":9.98386, "y":3.6672, "heading":2.7744, "vx":0.25906, "vy":1.27338, "omega":0.78156, "ax":-2.95762, "ay":0.40193, "alpha":-0.00902, "fx":[-36.96844,-36.96972,-36.97094,-36.97208], "fy":[5.11515,4.7673,5.10254,5.11137]}, + {"t":3.35138, "x":9.99024, "y":3.70512, "heading":2.79756, "vx":0.1714, "vy":1.28529, "omega":0.78129, "ax":-2.32314, "ay":-1.87709, "alpha":0.00051, "fx":[-29.03342,-29.06309,-29.03004,-29.03046], "fy":[-23.48988,-23.35083,-23.51587,-23.49795]}, + {"t":3.38102, "x":9.9943, "y":3.74239, "heading":2.82072, "vx":0.10254, "vy":1.22966, "omega":0.78131, "ax":-1.28098, "ay":-2.70383, "alpha":0.01728, "fx":[-16.00832,-16.05979,-15.9925,-15.98813], "fy":[-34.00081,-33.127,-34.04886,-34.01473]}, + {"t":3.41066, "x":9.99678, "y":3.77765, "heading":2.84388, "vx":0.06457, "vy":1.14951, "omega":0.78182, "ax":-0.77707, "ay":-2.89195, "alpha":0.00614, "fx":[-9.72478,-9.76135,-9.68976,-9.67781], "fy":[-36.25851,-35.71978,-36.33946,-36.2798]}, + {"t":3.4403, "x":9.99835, "y":3.81045, "heading":2.86705, "vx":0.04154, "vy":1.0638, "omega":0.782, "ax":-0.51265, "ay":-2.95173, "alpha":0.00043, "fx":[-6.43506,-6.47938,-6.37008,-6.34821], "fy":[-36.98472,-36.47394,-37.1125,-37.01545]}, + {"t":3.46994, "x":9.99936, "y":3.84068, "heading":2.89023, "vx":0.02634, "vy":0.97631, "omega":0.78201, "ax":-0.35379, "ay":-2.9758, "alpha":-0.01143, "fx":[-4.47237,-4.52071,-4.36494,-4.33146], "fy":[-37.22409,-36.88774,-37.41265,-37.26562]}, + {"t":3.49958, "x":9.99998, "y":3.86831, "heading":2.91341, "vx":0.01586, "vy":0.8881, "omega":0.78167, "ax":-0.24867, "ay":-2.98698, "alpha":-0.02525, "fx":[-3.18828,-3.24495,-3.02327,-2.97703], "fy":[-37.30353,-37.12124,-37.56769,-37.35669]}, + {"t":3.52922, "x":10.00034, "y":3.89332, "heading":2.93658, "vx":0.00849, "vy":0.79957, "omega":0.78093, "ax":-0.17424, "ay":-2.99264, "alpha":-0.04066, "fx":[-2.29648,-2.36436,-2.05528,-1.99563], "fy":[-37.319,-37.25294,-37.67614,-37.38411]}, + {"t":3.55886, "x":10.00052, "y":3.91571, "heading":2.95972, "vx":0.00332, "vy":0.71087, "omega":0.77972, "ax":-0.11886, "ay":-2.99565, "alpha":-0.06046, "fx":[-1.65429,-1.73317,-1.31422,-1.24124], "fy":[-37.2863,-37.37626,-37.7564,-37.3635]}, + {"t":3.5885, "x":10.00057, "y":3.93546, "heading":2.98283, "vx":-0.0002, "vy":0.62208, "omega":0.77793, "ax":-0.07609, "ay":-2.99727, "alpha":-0.08412, "fx":[-1.18351,-1.27312,-0.71672,-0.63135], "fy":[-37.22921,-37.48143,-37.83529,-37.31749]}, + {"t":3.61814, "x":10.00053, "y":3.95259, "heading":3.00589, "vx":-0.00246, "vy":0.53324, "omega":0.77544, "ax":-0.04209, "ay":-2.99812, "alpha":-0.11272, "fx":[-0.83943,-0.93793,-0.21158,-0.11578], "fy":[-37.1515,-37.58515,-37.92033,-37.24902]}, + {"t":3.64778, "x":10.00043, "y":3.96707, "heading":3.02888, "vx":-0.0037, "vy":0.44437, "omega":0.77209, "ax":-0.01443, "ay":-2.99853, "alpha":-0.14747, "fx":[-0.59573,-0.69965,0.23561,0.3385], "fy":[-37.05379,-37.69776,-38.01745,-37.15743]}, + {"t":3.67742, "x":10.00032, "y":3.97893, "heading":3.05176, "vx":-0.00413, "vy":0.3555, "omega":0.76772, "ax":0.00852, "ay":-2.99867, "alpha":-0.18943, "fx":[-0.43734,-0.54122,0.64986,0.75489], "fy":[-36.93684,-37.82869,-38.12631,-37.04185]}, + {"t":3.70706, "x":10.0002, "y":3.98815, "heading":3.07452, "vx":-0.00388, "vy":0.26661, "omega":0.76211, "ax":0.02786, "ay":-2.99866, "alpha":-0.24133, "fx":[-0.35697,-0.45238,1.05148,1.15101], "fy":[-36.79263,-37.9842,-38.2642,-36.89197]}, + {"t":3.7367, "x":10.0001, "y":3.99473, "heading":3.09711, "vx":-0.00305, "vy":0.17773, "omega":0.75496, "ax":0.04438, "ay":-2.99855, "alpha":-0.30425, "fx":[-0.35278,-0.42826,1.45805,1.54195], "fy":[-36.62344,-38.17226,-38.42439,-36.70738]}, + {"t":3.76634, "x":10.00003, "y":3.99868, "heading":3.11948, "vx":-0.00174, "vy":0.08886, "omega":0.74594, "ax":0.05865, "ay":-2.99838, "alpha":-0.38125, "fx":[-0.42788,-0.46727,1.88663,1.94088], "fy":[-36.42207,-38.40408,-38.61577,-36.47712]}, + {"t":3.79598, "x":10.0, "y":4.0, "heading":3.14159, "vx":0.0, "vy":-0.00002, "omega":0.73464, "ax":0.05863, "ay":-2.99734, "alpha":0.34783, "fx":[1.76492,1.76512,-0.30488,-0.29382], "fy":[-38.45515,-36.35319,-36.6078,-38.45063]}, + {"t":3.82562, "x":10.00003, "y":3.99868, "heading":-3.11982, "vx":0.00174, "vy":-0.08886, "omega":0.74495, "ax":0.04438, "ay":-2.99855, "alpha":0.27263, "fx":[1.38993,1.35196,-0.28354,-0.23939], "fy":[-38.23279,-36.61888,-36.81589,-38.25991]}, + {"t":3.85526, "x":10.0001, "y":3.99473, "heading":-3.09774, "vx":0.00305, "vy":-0.17773, "omega":0.75303, "ax":0.02786, "ay":-2.99866, "alpha":0.21585, "fx":[1.01786,0.95783,-0.32265,-0.25989], "fy":[-38.07009,-36.75843,-36.98851,-38.11597]}, + {"t":3.8849, "x":10.0002, "y":3.98815, "heading":-3.07542, "vx":0.00388, "vy":-0.26662, "omega":0.75943, "ax":0.00852, "ay":-2.99867, "alpha":0.16866, "fx":[0.63506,0.56494,-0.42209,-0.35172], "fy":[-37.93615,-36.87575,-37.13128,-37.99053]}, + {"t":3.91454, "x":10.00032, "y":3.97893, "heading":-3.05291, "vx":0.00413, "vy":-0.3555, "omega":0.76442, "ax":-0.01443, "ay":-2.99853, "alpha":0.13082, "fx":[0.2277,0.15599,-0.58759,-0.51738], "fy":[-37.83339,-36.96309,-37.24136,-37.88859]}, + {"t":3.94418, "x":10.00043, "y":3.96707, "heading":-3.03025, "vx":0.0037, "vy":-0.44437, "omega":0.7683, "ax":-0.04209, "ay":-2.99812, "alpha":0.0992, "fx":[-0.2214,-0.2881,-0.82948,-0.76574], "fy":[-37.74588,-37.0336,-37.33055,-37.79598]}, + {"t":3.97382, "x":10.00053, "y":3.95258, "heading":-3.00748, "vx":0.00246, "vy":-0.53324, "omega":0.77124, "ax":-0.07609, "ay":-2.99727, "alpha":0.07342, "fx":[-0.73483,-0.79202,-1.16536,-1.11251], "fy":[-37.67157,-37.08079,-37.39827,-37.7128]}, + {"t":4.00346, "x":10.00057, "y":3.93546, "heading":-2.98462, "vx":0.0002, "vy":-0.62208, "omega":0.77342, "ax":-0.11886, "ay":-2.99565, "alpha":0.05279, "fx":[-1.34486,-1.38968,-1.62364,-1.58476], "fy":[-37.60449,-37.09969,-37.44446,-37.63383]}, + {"t":4.0331, "x":10.00052, "y":3.91571, "heading":-2.96169, "vx":-0.00332, "vy":-0.71087, "omega":0.77498, "ax":-0.17424, "ay":-2.99264, "alpha":0.03713, "fx":[-2.10067,-2.13192,-2.25112,-2.22807], "fy":[-37.53667,-37.07759,-37.46542,-37.5525]}, + {"t":4.06274, "x":10.00034, "y":3.89332, "heading":-2.93872, "vx":-0.00849, "vy":-0.79957, "omega":0.77608, "ax":-0.24867, "ay":-2.98698, "alpha":0.0243, "fx":[-3.08342,-3.1005,-3.12813,-3.12153], "fy":[-37.44146,-37.02689,-37.43746,-37.44333]}, + {"t":4.09238, "x":9.99998, "y":3.86831, "heading":-2.91572, "vx":-0.01586, "vy":-0.8881, "omega":0.7768, "ax":-0.35379, "ay":-2.9758, "alpha":0.01784, "fx":[-4.43785,-4.44363,-4.39943,-4.40865], "fy":[-37.30045,-36.85601,-37.34437,-37.28927]}, + {"t":4.12202, "x":9.99936, "y":3.84068, "heading":-2.8927, "vx":-0.02634, "vy":-0.97631, "omega":0.77733, "ax":-0.51266, "ay":-2.95173, "alpha":0.01698, "fx":[-6.45058,-6.45069,-6.35448,-6.37708], "fy":[-37.01609,-36.48685,-37.08917,-36.99448]}, + {"t":4.15166, "x":9.99835, "y":3.81045, "heading":-2.86966, "vx":-0.04154, "vy":-1.0638, "omega":0.77784, "ax":-0.77708, "ay":-2.89195, "alpha":0.01356, "fx":[-9.76928,-9.76309,-9.64511,-9.67641], "fy":[-36.26111,-35.75795,-36.3448,-36.23364]}, + {"t":4.1813, "x":9.99678, "y":3.77765, "heading":-2.8466, "vx":-0.06457, "vy":-1.14951, "omega":0.77824, "ax":-1.28098, "ay":-2.70382, "alpha":0.03127, "fx":[-16.06031,-16.07485,-15.94041,-15.97356], "fy":[-33.99133,-33.1667,-34.0691,-33.96409]}, + {"t":4.21094, "x":9.9943, "y":3.74239, "heading":-2.82353, "vx":-0.10254, "vy":-1.22966, "omega":0.77917, "ax":-2.32315, "ay":-1.87708, "alpha":-0.00291, "fx":[-29.06684,-29.07611,-28.99675,-29.01781], "fy":[-23.47854,-23.38778,-23.52858,-23.45901]}, + {"t":4.24058, "x":9.99024, "y":3.70511, "heading":-2.80044, "vx":-0.1714, "vy":-1.28529, "omega":0.77908, "ax":-2.95762, "ay":0.40193, "alpha":-0.01942, "fx":[-36.97073,-36.97266,-36.96864,-36.9691], "fy":[5.11026,4.76856,5.10331,5.11453]}, + {"t":4.27022, "x":9.98386, "y":3.6672, "heading":-2.77735, "vx":-0.25906, "vy":-1.27338, "omega":0.7785, "ax":-2.90607, "ay":0.69539, "alpha":-0.00889, "fx":[-36.29408,-36.31723,-36.35406,-36.33798], "fy":[8.75529,8.49426,8.78384,8.73615]}, + {"t":4.29986, "x":9.97491, "y":3.62976, "heading":-2.75427, "vx":-0.3452, "vy":-1.25277, "omega":0.77824, "ax":-2.85404, "ay":0.89347, "alpha":0.00792, "fx":[-35.61525,-35.6555,-35.7316,-35.69973], "fy":[11.1806,11.12053,11.23525,11.13737]}, + {"t":4.3295, "x":9.96342, "y":3.59302, "heading":-2.73121, "vx":-0.42979, "vy":-1.22629, "omega":0.77847, "ax":-2.78805, "ay":1.08713, "alpha":0.01241, "fx":[-34.76129,-34.82438,-34.93255,-34.88439], "fy":[13.60628,13.53192,13.68087,13.53729]}, + {"t":4.35914, "x":9.94946, "y":3.55715, "heading":-2.70813, "vx":-0.51243, "vy":-1.19406, "omega":0.77884, "ax":-2.70812, "ay":1.27655, "alpha":0.00728, "fx":[-33.73164,-33.82518,-33.95703,-33.89191], "fy":[16.02157,15.77038,16.11023,15.92557]}, + {"t":4.38878, "x":9.93308, "y":3.52232, "heading":-2.68505, "vx":-0.5927, "vy":-1.15623, "omega":0.77906, "ax":-2.60643, "ay":1.47525, "alpha":0.00597, "fx":[-32.43369,-32.5486,-32.71084,-32.62828], "fy":[18.53586,18.18082,18.63161,18.41434]}, + {"t":4.41842, "x":9.91437, "y":3.48869, "heading":-2.66195, "vx":-0.66995, "vy":-1.1125, "omega":0.77924, "ax":-2.38624, "ay":1.81127, "alpha":0.01258, "fx":[-29.65688,-29.78767,-29.98439,-29.88325], "fy":[22.7319,22.41469,22.82983,22.58684]}, + {"t":4.44806, "x":9.89346, "y":3.45652, "heading":-2.63886, "vx":-0.74068, "vy":-1.05881, "omega":0.77961, "ax":-2.07394, "ay":2.16281, "alpha":0.02409, "fx":[-25.72755,-25.87988,-26.10567,-25.98381], "fy":[27.10064,26.90829,27.1985,26.93331]}, + {"t":4.47771, "x":9.8706, "y":3.42608, "heading":-2.61575, "vx":-0.80215, "vy":-0.99471, "omega":0.78032, "ax":-1.80629, "ay":2.39157, "alpha":0.03506, "fx":[-22.35655,-22.52928,-22.78693,-22.64178], "fy":[29.93797,29.85724,30.03511,29.74796]}, + {"t":4.50735, "x":9.84603, "y":3.39765, "heading":-2.59262, "vx":-0.85569, "vy":-0.92382, "omega":0.78136, "ax":-1.5935, "ay":2.53881, "alpha":0.04275, "fx":[-19.66929,-19.86713,-20.15509,-19.98371], "fy":[31.772,31.74286,31.86752,31.55808]}, + {"t":4.53699, "x":9.81997, "y":3.37138, "heading":-2.56946, "vx":-0.90292, "vy":-0.84857, "omega":0.78263, "ax":-1.42576, "ay":2.63704, "alpha":0.05247, "fx":[-17.54336,-17.76649,-18.08973,-17.88859], "fy":[32.98796,33.03557,33.08103,32.74741]}, + {"t":4.56663, "x":9.79258, "y":3.34739, "heading":-2.54626, "vx":-0.94518, "vy":-0.77041, "omega":0.78418, "ax":-1.29225, "ay":2.70526, "alpha":0.06095, "fx":[-15.84023,-16.09607,-16.45621,-16.22023], "fy":[33.83874,33.92849,33.92861,33.56695]}, + {"t":4.59627, "x":9.76399, "y":3.32574, "heading":-2.52302, "vx":-0.98349, "vy":-0.69022, "omega":0.78599, "ax":-1.18442, "ay":2.7544, "alpha":0.0719, "fx":[-14.4517,-14.74647,-15.15029,-14.87253], "fy":[34.4478,34.6006,34.53348,34.13817]}, + {"t":4.62591, "x":9.73432, "y":3.30649, "heading":-2.49972, "vx":-1.01859, "vy":-0.60858, "omega":0.78812, "ax":-1.09597, "ay":2.79096, "alpha":0.08449, "fx":[-13.29637,-13.64024,-14.09554,-13.76655], "fy":[34.90213,35.1178,34.98223,34.54562]}, + {"t":4.65555, "x":9.70365, "y":3.28968, "heading":-2.47636, "vx":-1.05108, "vy":-0.52586, "omega":0.79063, "ax":-1.02238, "ay":2.8189, "alpha":0.09978, "fx":[-12.31475,-12.7206,-13.23807,-12.84533], "fy":[35.25014,35.53734,35.32253,34.83487]}, + {"t":4.68519, "x":9.67205, "y":3.27533, "heading":-2.45293, "vx":-1.08138, "vy":-0.44231, "omega":0.79358, "ax":-0.96032, "ay":2.84076, "alpha":0.11834, "fx":[-11.46232,-11.94677,-12.53995,-12.06718], "fy":[35.52487,35.8915,35.58628,35.03537]}, + {"t":4.71483, "x":9.63957, "y":3.26347, "heading":-2.42941, "vx":-1.10984, "vy":-0.35811, "omega":0.79709, "ax":-0.89915, "ay":2.85988, "alpha":0.95749, "fx":[-7.08794,-10.86113,-15.36027,-11.64837], "fy":[35.70301,39.36414,35.97024,31.95668]}, + {"t":4.75227, "x":9.59739, "y":3.25207, "heading":-2.39957, "vx":-1.14351, "vy":-0.25103, "omega":0.83294, "ax":-0.81786, "ay":2.88514, "alpha":0.73122, "fx":[-7.04679,-10.02971,-13.38374,-10.43297], "fy":[36.10397,38.8334,36.14249,33.17701]}, + {"t":4.78971, "x":9.554, "y":3.24469, "heading":-2.36838, "vx":-1.17413, "vy":-0.14301, "omega":0.86032, "ax":-0.71252, "ay":2.91277, "alpha":0.5553, "fx":[-6.47424,-8.84189,-11.32916,-8.98086], "fy":[36.51481,38.48092,36.42102,34.22186]}, + {"t":4.82715, "x":9.50954, "y":3.24138, "heading":-2.33617, "vx":-1.20081, "vy":-0.03396, "omega":0.88111, "ax":-0.5721, "ay":2.94335, "alpha":0.42064, "fx":[-5.28998,-7.17031,-9.00603,-7.13891], "fy":[36.93957,38.31976,36.77373,35.13468]}, + {"t":4.86459, "x":9.46418, "y":3.24217, "heading":-2.30318, "vx":-1.22223, "vy":0.07624, "omega":0.89686, "ax":-0.37747, "ay":2.97429, "alpha":0.31795, "fx":[-3.29335,-4.78839,-6.13924,-4.65249], "fy":[37.34724,38.28981,37.14985,35.92776]}, + {"t":4.90203, "x":9.41816, "y":3.24711, "heading":-2.2696, "vx":-1.23636, "vy":0.1876, "omega":0.90876, "ax":-0.0951, "ay":2.99624, "alpha":0.23917, "fx":[-0.09576,-1.28735,-2.28025,-1.09172], "fy":[37.63389,38.23398,37.43114,36.51284]}, + {"t":4.93947, "x":9.3718, "y":3.25623, "heading":-2.23558, "vx":-1.23992, "vy":0.29978, "omega":0.91771, "ax":0.33246, "ay":2.97867, "alpha":0.17898, "fx":[4.99599,4.04495,3.31291,4.26907], "fy":[37.42205,37.75394,37.22896,36.52861]}, + {"t":4.97691, "x":9.32561, "y":3.26955, "heading":-2.20122, "vx":-1.22747, "vy":0.41131, "omega":0.92442, "ax":0.95413, "ay":2.84038, "alpha":0.12722, "fx":[12.57322,11.81602,11.27157,12.04562], "fy":[35.7234,35.74914,35.54565,35.00102]}, + {"t":5.01435, "x":9.28032, "y":3.28694, "heading":-2.16661, "vx":-1.19175, "vy":0.51765, "omega":0.92918, "ax":1.30618, "ay":2.69543, "alpha":0.09913, "fx":[16.82415,16.2275,15.81555,16.44185], "fy":[33.88759,33.86874,33.72154,33.29376]}, + {"t":5.05179, "x":9.23662, "y":3.30821, "heading":-2.13182, "vx":-1.14285, "vy":0.61857, "omega":0.93289, "ax":1.53592, "ay":2.56946, "alpha":0.07888, "fx":[19.58306,19.11098,18.79811,19.30378], "fy":[32.28853,32.25871,32.12975,31.79603]}, + {"t":5.08923, "x":9.19491, "y":3.33317, "heading":-2.09689, "vx":-1.08534, "vy":0.71477, "omega":0.93584, "ax":1.75018, "ay":2.42503, "alpha":0.05843, "fx":[22.17581,21.7977,21.56443,21.97124], "fy":[30.48119,30.36738,30.33012,30.0728]}, + {"t":5.12667, "x":9.1555, "y":3.36163, "heading":-2.06185, "vx":-1.01981, "vy":0.80556, "omega":0.93803, "ax":1.94895, "ay":2.26125, "alpha":0.04455, "fx":[24.59263,24.29367,24.1181,24.44324], "fy":[28.41939,28.28339,28.2778,28.08208]}, + {"t":5.16411, "x":9.11868, "y":3.39337, "heading":-2.02673, "vx":-0.94684, "vy":0.89023, "omega":0.9397, "ax":2.12732, "ay":2.07734, "alpha":0.06043, "fx":[26.7706,26.52642,26.40647,26.66248], "fy":[25.98825,26.30662,25.85864,25.71341]}, + {"t":5.20155, "x":9.08472, "y":3.42816, "heading":-1.99155, "vx":-0.8672, "vy":0.968, "omega":0.94196, "ax":2.26955, "ay":1.86656, "alpha":0.04358, "fx":[28.50622,28.32195,28.22297,28.42642], "fy":[23.37466,23.54723,23.25652,23.14978]}, + {"t":5.23899, "x":9.05385, "y":3.46571, "heading":-1.95628, "vx":-0.78222, "vy":1.03789, "omega":0.94359, "ax":2.26241, "ay":1.56855, "alpha":0.10847, "fx":[28.38307,28.23662,28.17401,28.32675], "fy":[19.30873,20.77721,19.20728,19.13446]}, + {"t":5.27643, "x":9.02615, "y":3.50567, "heading":-1.92095, "vx":-0.69752, "vy":1.09661, "omega":0.94765, "ax":0.9362, "ay":0.5749, "alpha":0.0092, "fx":[11.78326,11.66373,11.62148,11.7415], "fy":[7.29601,7.08452,7.20752,7.15705]}, + {"t":5.31387, "x":9.00069, "y":3.54713, "heading":-1.88547, "vx":-0.66247, "vy":1.11814, "omega":0.948, "ax":0.06151, "ay":0.03636, "alpha":-0.03804, "fx":[0.82743,0.73831,0.71028,0.79936], "fy":[0.74515,-0.2432,0.67446,0.64142]}, + {"t":5.35131, "x":8.97593, "y":3.58902, "heading":-1.84998, "vx":-0.66016, "vy":1.1195, "omega":0.94658, "ax":0.02192, "ay":0.01292, "alpha":-0.00557, "fx":[0.31215,0.25246,0.23592,0.29561], "fy":[0.2692,-0.03698,0.21688,0.19675]}, + {"t":5.38875, "x":8.95122, "y":3.63094, "heading":-1.81454, "vx":-0.65934, "vy":1.11998, "omega":0.94637, "ax":-0.00666, "ay":-0.00392, "alpha":-0.00073, "fx":[-0.05865,-0.09836,-0.10781,-0.06809], "fy":[0.01119,-0.14237,-0.02654,-0.03832]}, + {"t":5.42619, "x":8.92653, "y":3.67287, "heading":-1.77911, "vx":-0.65959, "vy":1.11984, "omega":0.94634, "ax":0.00104, "ay":0.00061, "alpha":0.00442, "fx":[0.02813,0.00287,-0.00212,0.02314], "fy":[0.02412,0.01739,-0.00219,-0.00868]}, + {"t":5.46363, "x":8.90184, "y":3.7148, "heading":-1.74368, "vx":-0.65955, "vy":1.11986, "omega":0.94651, "ax":-0.00013, "ay":-0.00007, "alpha":0.00373, "fx":[0.00746,-0.00817,-0.0106,0.00503], "fy":[0.00541,0.01909,-0.01244,-0.01576]}, + {"t":5.50107, "x":8.87715, "y":3.75673, "heading":-1.70824, "vx":-0.65956, "vy":1.11986, "omega":0.94664, "ax":0.00034, "ay":0.0002, "alpha":0.00304, "fx":[0.00932,0.0001,-0.00091,0.00831], "fy":[0.00261,0.02685,-0.00904,-0.01052]}, + {"t":5.53851, "x":8.85245, "y":3.79865, "heading":-1.6728, "vx":-0.65955, "vy":1.11986, "omega":0.94676, "ax":-0.00001, "ay":-0.00001, "alpha":0.002, "fx":[0.00252,-0.00258,-0.00286,0.00224], "fy":[-0.00122,0.01821,-0.00845,-0.00894]}, + {"t":5.57595, "x":8.82776, "y":3.84058, "heading":-1.63735, "vx":-0.65955, "vy":1.11986, "omega":0.94683, "ax":-0.00003, "ay":-0.00002, "alpha":0.0012, "fx":[0.00079,-0.00169,-0.00163,0.00085], "fy":[-0.0017,0.01221,-0.00575,-0.00574]}, + {"t":5.61339, "x":8.80306, "y":3.88251, "heading":-1.6019, "vx":-0.65955, "vy":1.11986, "omega":0.94688, "ax":-0.00006, "ay":-0.00003, "alpha":0.00056, "fx":[-0.00043,-0.00119,-0.001,-0.00023], "fy":[-0.00166,0.00647,-0.00336,-0.00314]}, + {"t":5.65083, "x":8.77837, "y":3.92444, "heading":-1.56645, "vx":-0.65955, "vy":1.11986, "omega":0.9469, "ax":-0.00003, "ay":-0.00002, "alpha":0.00006, "fx":[-0.00073,-0.00023,-0.00002,-0.00053], "fy":[-0.00118,0.00196,-0.00096,-0.00071]}, + {"t":5.68828, "x":8.75368, "y":3.96637, "heading":-1.531, "vx":-0.65955, "vy":1.11986, "omega":0.9469, "ax":0.0, "ay":0.0, "alpha":-0.00038, "fx":[-0.00095,0.00072,0.00085,-0.00082], "fy":[-0.00075,-0.00211,0.00129,0.00145]}, + {"t":5.72572, "x":8.72898, "y":4.00829, "heading":-1.49554, "vx":-0.65955, "vy":1.11986, "omega":0.94689, "ax":0.00002, "ay":0.00001, "alpha":-0.00084, "fx":[-0.00125,0.00179,0.00175,-0.00129], "fy":[-0.00046,-0.00621,0.00367,0.0036]}, + {"t":5.76316, "x":8.70429, "y":4.05022, "heading":-1.46009, "vx":-0.65955, "vy":1.11986, "omega":0.94686, "ax":0.00005, "ay":0.00003, "alpha":-0.00138, "fx":[-0.00166,0.0032,0.00285,-0.00202], "fy":[-0.00035,-0.01069,0.00645,0.00598]}, + {"t":5.8006, "x":8.6796, "y":4.09215, "heading":-1.42464, "vx":-0.65955, "vy":1.11986, "omega":0.9468, "ax":0.00001, "ay":0.00001, "alpha":-0.00206, "fx":[-0.00314,0.0043,0.00339,-0.00406], "fy":[-0.00107,-0.01636,0.00944,0.00829]}, + {"t":5.83804, "x":8.6549, "y":4.13408, "heading":-1.38919, "vx":-0.65955, "vy":1.11986, "omega":0.94673, "ax":0.00001, "ay":0.0, "alpha":-0.00288, "fx":[-0.00454,0.00658,0.00472,-0.0064], "fy":[-0.00251,-0.02149,0.01323,0.01098]}, + {"t":5.87548, "x":8.63021, "y":4.17601, "heading":-1.35375, "vx":-0.65955, "vy":1.11986, "omega":0.94662, "ax":-0.00043, "ay":-0.00025, "alpha":-0.00393, "fx":[-0.01179,0.0045,0.00109,-0.01519], "fy":[-0.00858,-0.0292,0.01458,0.0106]}, + {"t":5.91292, "x":8.60551, "y":4.21793, "heading":-1.3183, "vx":-0.65956, "vy":1.11985, "omega":0.94647, "ax":0.00036, "ay":0.00021, "alpha":-0.00476, "fx":[-0.00433,0.01914,0.01329,-0.01018], "fy":[-0.01183,-0.01446,0.02176,0.01509]}, + {"t":5.95036, "x":8.58082, "y":4.25986, "heading":-1.28287, "vx":-0.65955, "vy":1.11986, "omega":0.94629, "ax":-0.0015, "ay":-0.00089, "alpha":-0.00586, "fx":[-0.03062,0.00263,-0.00697,-0.04022], "fy":[-0.03911,-0.01233,0.00896,-0.00178]}, + {"t":5.9878, "x":8.55613, "y":4.30179, "heading":-1.24744, "vx":-0.65961, "vy":1.11983, "omega":0.94607, "ax":0.0093, "ay":0.00547, "alpha":-0.00369, "fx":[0.10058,0.14712,0.13182,0.08528], "fy":[-0.01317,0.19399,0.05481,0.03804]}, + {"t":6.02524, "x":8.53144, "y":4.34372, "heading":-1.21202, "vx":-0.65926, "vy":1.12003, "omega":0.94594, "ax":-0.03185, "ay":-0.01877, "alpha":-0.00369, "fx":[-0.41825,-0.35458,-0.3781,-0.44177], "fy":[-0.36632,-0.0034,-0.27173,-0.29715]}, + {"t":6.06268, "x":8.50673, "y":4.38564, "heading":-1.1766, "vx":-0.66045, "vy":1.11933, "omega":0.9458, "ax":-0.06896, "ay":-0.0408, "alpha":0.00924, "fx":[-0.88752,-0.8007,-0.83652,-0.92322], "fy":[-0.85387,0.29938,-0.72386,-0.76148]}, + {"t":6.10012, "x":8.48195, "y":4.42752, "heading":-1.14119, "vx":-0.66303, "vy":1.1178, "omega":0.94614, "ax":-1.09918, "ay":-0.67999, "alpha":-0.02119, "fx":[-13.7696,-13.65891,-13.70951,-13.82077], "fy":[-8.59225,-8.5136,-8.42037,-8.47322]}, + {"t":6.13756, "x":8.45636, "y":4.4689, "heading":-1.10577, "vx":-0.70419, "vy":1.09234, "omega":0.94535, "ax":-2.28277, "ay":-1.60522, "alpha":-0.05354, "fx":[-28.56607,-28.43503,-28.49946,-28.63818], "fy":[-19.83408,-21.12956,-19.61314,-19.68417]}, + {"t":6.175, "x":8.4284, "y":4.50867, "heading":-1.07037, "vx":-0.78965, "vy":1.03224, "omega":0.94335, "ax":-2.25993, "ay":-1.88631, "alpha":-0.03655, "fx":[-28.28169,-28.12277,-28.20845,-28.38339], "fy":[-23.69613,-23.7025,-23.41058,-23.50639]}, + {"t":6.21244, "x":8.39725, "y":4.54599, "heading":-1.03505, "vx":-0.87427, "vy":0.96162, "omega":0.94198, "ax":-2.11306, "ay":-2.094, "alpha":-0.0469, "fx":[-26.44973,-26.24309,-26.3711,-26.58918], "fy":[-26.31958,-26.33999,-25.95654,-26.08402]}, + {"t":6.24988, "x":8.36303, "y":4.58053, "heading":-0.99978, "vx":-0.95338, "vy":0.88322, "omega":0.94022, "ax":-1.9326, "ay":-2.27607, "alpha":-0.05157, "fx":[-24.19308,-23.94382,-24.10954,-24.38358], "fy":[-28.77609,-28.23126,-28.313,-28.48338]}, + {"t":6.28732, "x":8.32598, "y":4.612, "heading":-0.96458, "vx":-1.02574, "vy":0.798, "omega":0.93829, "ax":-1.73236, "ay":-2.43819, "alpha":-0.06924, "fx":[-21.69118,-21.37298,-21.60459,-21.9493], "fy":[-30.84365,-30.33094,-30.2535,-30.48119]}, + {"t":6.32476, "x":8.28636, "y":4.64017, "heading":-0.92945, "vx":-1.0906, "vy":0.70672, "omega":0.9357, "ax":-1.51681, "ay":-2.581, "alpha":-0.08987, "fx":[-18.99596,-18.59084,-18.90899,-19.3446], "fy":[-32.72647,-32.07305,-31.97264,-32.27787]}, + {"t":6.3622, "x":8.24447, "y":4.66482, "heading":-0.89442, "vx":-1.14739, "vy":0.61008, "omega":0.93233, "ax":-1.27797, "ay":-2.70905, "alpha":-0.11791, "fx":[-16.01227,-15.47715,-15.9266,-16.48237], "fy":[-34.45929,-33.59532,-33.4932,-33.90471]}, + {"t":6.39964, "x":8.20062, "y":4.68577, "heading":-0.85951, "vx":-1.19524, "vy":0.50866, "omega":0.92792, "ax":-0.74825, "ay":-2.90153, "alpha":-0.156, "fx":[-9.39322,-8.68664,-9.30778,-10.02481], "fy":[-36.99831,-36.01096,-35.75289,-36.31445]}, + {"t":6.43708, "x":8.15534, "y":4.70278, "heading":-0.82477, "vx":-1.22325, "vy":0.40002, "omega":0.92208, "ax":-0.15177, "ay":-2.99342, "alpha":-0.20669, "fx":[-1.93596,-1.00886,-1.85833,-2.78528], "fy":[-38.30835,-37.22226,-36.68359,-37.45692]}, + {"t":6.47452, "x":8.10944, "y":4.71565, "heading":-0.79025, "vx":-1.22893, "vy":0.28795, "omega":0.91434, "ax":0.22983, "ay":-2.989, "alpha":-0.27315, "fx":[2.84732,4.04846,2.89543,1.70004], "fy":[-38.49527,-37.16979,-36.35948,-37.42552]}, + {"t":6.51196, "x":8.06358, "y":4.72434, "heading":-0.75601, "vx":-1.22033, "vy":0.17604, "omega":0.90411, "ax":0.48017, "ay":-2.95951, "alpha":-0.3607, "fx":[6.00874,7.5531,5.99143,4.45516], "fy":[-38.45762,-36.76552,-35.64365,-37.10866]}, + {"t":6.5494, "x":8.01823, "y":4.72886, "heading":-0.72216, "vx":-1.20235, "vy":0.06523, "omega":0.89061, "ax":0.65324, "ay":-2.92646, "alpha":-0.47556, "fx":[8.23183,10.20631,8.09512,6.12881], "fy":[-38.48014,-36.28527,-34.77689,-36.78083]}, + {"t":6.58684, "x":7.97367, "y":4.72925, "heading":-0.68882, "vx":-1.17789, "vy":-0.04434, "omega":0.8728, "ax":0.77873, "ay":-2.89581, "alpha":-0.62519, "fx":[9.89991,12.41145,9.56484,7.06012], "fy":[-38.66268,-35.78992,-33.80904,-36.52893]}, + {"t":6.62428, "x":7.93012, "y":4.72556, "heading":-0.65614, "vx":-1.14874, "vy":-0.15276, "omega":0.8494, "ax":0.87334, "ay":-2.86886, "alpha":-0.82044, "fx":[11.2379,14.41838,10.59312,7.41774], "fy":[-39.06204,-35.27211,-32.71369,-36.39515]}, + {"t":6.66172, "x":7.88772, "y":4.71783, "heading":-0.62434, "vx":-1.11604, "vy":-0.26017, "omega":0.81868, "ax":0.94698, "ay":-2.84553, "alpha":-1.07361, "fx":[12.39146,16.40119,11.28163,7.27479], "fy":[-39.71454,-34.71526,-31.44371,-36.40314]}, + {"t":6.69917, "x":7.8466, "y":4.70609, "heading":-0.59369, "vx":-1.08058, "vy":-0.36671, "omega":0.77848, "ax":1.00211, "ay":-2.82497, "alpha":-0.00744, "fx":[12.52832,12.55085,12.51667,12.5099], "fy":[-35.39423,-35.1074,-35.36614,-35.38071]}, + {"t":6.72892, "x":7.81489, "y":4.69393, "heading":-0.57052, "vx":-1.05076, "vy":-0.45078, "omega":0.77826, "ax":1.05949, "ay":-2.8052, "alpha":-0.01459, "fx":[13.25205,13.29719,13.22969,13.19556], "fy":[-35.15741,-34.92908,-35.05924,-35.11427]}, + {"t":6.75868, "x":7.78408, "y":4.67927, "heading":-0.54736, "vx":-1.01923, "vy":-0.53426, "omega":0.77783, "ax":1.1268, "ay":-2.7787, "alpha":-0.02208, "fx":[14.09977,14.16969,14.0639,14.00671], "fy":[-34.85465,-34.57364,-34.70808,-34.79873]}, + {"t":6.78844, "x":7.75425, "y":4.66214, "heading":-0.52421, "vx":-0.9857, "vy":-0.61695, "omega":0.77717, "ax":1.20739, "ay":-2.74447, "alpha":-0.02953, "fx":[15.11417,15.20651,15.06324,14.98575], "fy":[-34.45636,-34.12304,-34.25902,-34.385]}, + {"t":6.8182, "x":7.72545, "y":4.64257, "heading":-0.50108, "vx":-0.94977, "vy":-0.69863, "omega":0.77629, "ax":1.30528, "ay":-2.69907, "alpha":-0.03717, "fx":[16.34576,16.45954,16.27751,16.18141], "fy":[-33.91969,-33.52754,-33.6718,-33.8343]}, + {"t":6.84796, "x":7.69777, "y":4.62058, "heading":-0.47798, "vx":-0.91092, "vy":-0.77895, "omega":0.77518, "ax":1.42607, "ay":-2.63697, "alpha":-0.04492, "fx":[17.86514,17.99873,17.77671,17.66281], "fy":[-33.17257,-32.72931,-32.87254,-33.07396]}, + {"t":6.87772, "x":7.67129, "y":4.59623, "heading":-0.45491, "vx":-0.86848, "vy":-0.85742, "omega":0.77385, "ax":1.5775, "ay":-2.5489, "alpha":-0.05404, "fx":[19.76881,19.92465,19.65672,19.52492], "fy":[-32.11016,-31.58353,-31.75296,-31.99851]}, + {"t":6.90748, "x":7.64614, "y":4.56959, "heading":-0.43188, "vx":-0.82154, "vy":-0.93328, "omega":0.77224, "ax":1.76993, "ay":-2.41876, "alpha":-0.06478, "fx":[22.18709,22.36684,22.04667,21.89603], "fy":[-30.53013,-29.89602,-30.10708,-30.40452]}, + {"t":6.93724, "x":7.62248, "y":4.54074, "heading":-0.4089, "vx":-0.76886, "vy":-1.00526, "omega":0.77031, "ax":2.01505, "ay":-2.21799, "alpha":-0.07596, "fx":[25.2689,25.46774,25.09351,24.92251], "fy":[-28.06291,-27.35342,-27.56159,-27.92169]}, + {"t":6.967, "x":7.60049, "y":4.50984, "heading":-0.38598, "vx":-0.7089, "vy":-1.07127, "omega":0.76805, "ax":2.31646, "ay":-1.89998, "alpha":-0.09182, "fx":[29.05873,29.27928,28.83903,28.64598], "fy":[-24.16372,-23.26698,-23.56482,-24.00349]}, + {"t":6.99676, "x":7.58042, "y":4.47712, "heading":-0.36312, "vx":-0.63996, "vy":-1.12781, "omega":0.76532, "ax":2.6148, "ay":-1.46076, "alpha":-0.11302, "fx":[32.81671,33.06389,32.5382,32.32139], "fy":[-18.77928,-17.60636,-18.05746,-18.595]}, + {"t":7.02652, "x":7.56253, "y":4.44291, "heading":-0.34034, "vx":-0.56214, "vy":-1.17128, "omega":0.76195, "ax":2.73996, "ay":-1.20736, "alpha":-0.13137, "fx":[34.42226,34.69327,34.06332,33.8194], "fy":[-15.66223,-14.47742,-14.78116,-15.44728]}, + {"t":7.05628, "x":7.54701, "y":4.40752, "heading":-0.31767, "vx":-0.4806, "vy":-1.20721, "omega":0.75804, "ax":2.81639, "ay":-1.01265, "alpha":-0.14956, "fx":[35.43551,35.72416,34.96756,34.69217], "fy":[-13.25395,-12.19803,-12.17844,-13.00229]}, + {"t":7.08604, "x":7.53396, "y":4.37114, "heading":-0.29511, "vx":-0.39679, "vy":-1.23735, "omega":0.75359, "ax":2.87875, "ay":-0.81261, "alpha":-0.17943, "fx":[36.28934,36.60485,35.67683,35.36651], "fy":[-10.84738,-9.70481,-9.5266,-10.55181]}, + {"t":7.1158, "x":7.52343, "y":4.33396, "heading":-0.27268, "vx":-0.31112, "vy":-1.26153, "omega":0.74825, "ax":2.97442, "ay":-0.29665, "alpha":-0.23731, "fx":[37.58667,37.92242,36.77451,36.43752], "fy":[-4.69185,-2.74317,-3.06111,-4.33616]}, + {"t":7.14556, "x":7.51548, "y":4.29629, "heading":-0.25042, "vx":-0.2226, "vy":-1.27036, "omega":0.74119, "ax":2.5323, "ay":1.5897, "alpha":-0.25473, "fx":[32.22575,32.56555,31.07574,30.748], "fy":[18.9918,20.04772,20.99719,19.4481]}, + {"t":7.17532, "x":7.50998, "y":4.25919, "heading":-0.22836, "vx":-0.14724, "vy":-1.22305, "omega":0.73361, "ax":1.63825, "ay":2.50467, "alpha":-0.31227, "fx":[21.23831,21.65082,19.69641,19.32694], "fy":[30.3026,31.44524,32.6664,30.81919]}, + {"t":7.20508, "x":7.50632, "y":4.2239, "heading":-0.20653, "vx":-0.09848, "vy":-1.14851, "omega":0.72432, "ax":1.06635, "ay":2.79859, "alpha":-0.38715, "fx":[14.30719,14.77867,12.33581,11.89592], "fy":[33.76824,35.24865,36.58556,34.327]}, + {"t":7.23484, "x":7.50387, "y":4.19096, "heading":-0.18497, "vx":-0.06675, "vy":-1.06523, "omega":0.7128, "ax":0.72985, "ay":2.90581, "alpha":-0.48858, "fx":[10.37288,10.89249,7.86906,7.35809], "fy":[34.77875,36.95893,38.16957,35.38335]}, + {"t":7.2646, "x":7.5022, "y":4.16054, "heading":-0.16376, "vx":-0.04503, "vy":-0.97875, "omega":0.69826, "ax":0.51745, "ay":2.95183, "alpha":-0.61181, "fx":[8.06038,8.62583,4.883,4.30337], "fy":[34.96946,37.93276,39.06737,35.62172]}, + {"t":7.29436, "x":7.50109, "y":4.13272, "heading":-0.14298, "vx":-0.02963, "vy":-0.89091, "omega":0.68005, "ax":0.3734, "ay":2.97401, "alpha":-0.76024, "fx":[6.69027,7.29667,2.66409,2.01904], "fy":[34.80662,38.62871,39.76175,35.50359]}, + {"t":7.32412, "x":7.50037, "y":4.10753, "heading":-0.12274, "vx":-0.01852, "vy":-0.8024, "omega":0.65742, "ax":0.26998, "ay":2.98556, "alpha":-0.94341, "fx":[5.93973,6.57029,0.84708,0.14178], "fy":[34.41394,39.31029,40.40457,35.14921]}, + {"t":7.35388, "x":7.49994, "y":4.08497, "heading":-0.10318, "vx":-0.01048, "vy":-0.71355, "omega":0.62935, "ax":0.19238, "ay":2.99185, "alpha":-1.16599, "fx":[5.64815,6.28087,-0.77573,-1.53414], "fy":[33.85843,40.02523,41.08917,34.61958]}, + {"t":7.38364, "x":7.49972, "y":4.06506, "heading":-0.08445, "vx":-0.00476, "vy":-0.62451, "omega":0.59465, "ax":0.13213, "ay":2.99534, "alpha":-1.43777, "fx":[5.74044,6.34222,-2.33664,-3.13943], "fy":[33.14261,40.83604,41.87757,33.91061]}, + {"t":7.4134, "x":7.49963, "y":4.0478, "heading":-0.06675, "vx":-0.00083, "vy":-0.53537, "omega":0.55186, "ax":0.08405, "ay":2.99725, "alpha":-1.76861, "fx":[6.18986,6.71336,-3.93154,-4.76921], "fy":[32.25705,41.80616,42.7908,33.00844]}, + {"t":7.44316, "x":7.49965, "y":4.0332, "heading":-0.05033, "vx":0.00167, "vy":-0.44618, "omega":0.49923, "ax":0.04482, "ay":2.99824, "alpha":-2.16899, "fx":[6.99674,7.38141,-5.63517,-6.50217], "fy":[31.18943,42.96048,43.86957,31.8924]}, + {"t":7.47292, "x":7.49972, "y":4.02125, "heading":-0.03547, "vx":0.00301, "vy":-0.35695, "omega":0.43468, "ax":0.01221, "ay":2.99867, "alpha":-2.65409, "fx":[8.18448,8.35001,-7.51213,-8.41176], "fy":[29.8999,44.35569,45.15893,30.51891]}, + {"t":7.50268, "x":7.49981, "y":4.01195, "heading":-0.02253, "vx":0.00337, "vy":-0.26771, "omega":0.35569, "ax":-0.0153, "ay":2.99876, "alpha":-3.23774, "fx":[9.78885,9.63794,-9.61809,-10.57388], "fy":[28.35928,46.02756,46.69461,28.85635]}, + {"t":7.53244, "x":7.4999, "y":4.00531, "heading":-0.01195, "vx":0.00292, "vy":-0.17847, "omega":0.25934, "ax":-0.03883, "ay":2.99863, "alpha":-3.93792, "fx":[11.85796,11.27438,-12.00089,-13.07289], "fy":[26.51378,48.02325,48.53595,26.8586]}, + {"t":7.5622, "x":7.49997, "y":4.00133, "heading":-0.00423, "vx":0.00176, "vy":-0.08923, "omega":0.14215, "ax":-0.05917, "ay":2.99837, "alpha":-4.77658, "fx":[14.44374,13.23579,-14.78721,-15.85094], "fy":[24.22771,50.54387,50.69085,24.4563]}, + {"t":7.59196, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/deploy/choreo/LineLessJiggleTest.traj b/deploy/choreo/LineLessJiggleTest.traj new file mode 100644 index 00000000..9528303a --- /dev/null +++ b/deploy/choreo/LineLessJiggleTest.traj @@ -0,0 +1,217 @@ +{ + "name":"LineLessJiggleTest", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.5, "y":4.0, "heading":0.0, "intervals":63, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":9.5, "y":4.0, "heading":3.141592653589793, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":10.0, "y":4.0, "heading":3.141592653589793, "intervals":63, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":8.0, "y":4.0, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.5, "y":4.0, "heading":0.0, "intervals":28, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":1.3}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":3.0}}, "enabled":true}, + {"from":"first", "to":1, "data":{"type":"MaxAngularVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInLane", "props":{"tolerance":0.01}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepOutCircle", "props":{"x":4.491, "y":4.026, "r":1.0}}, "enabled":true}, + {"from":1, "to":2, "data":{"type":"MaxAngularVelocity", "props":{"max":0.5}}, "enabled":true}, + {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":3, "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":0.5}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading", "val":0.0}, "intervals":63, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x + 2 m", "val":9.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading + 180 deg", "val":3.141592653589793}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x + 2.5 m", "val":10.0}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading + 180 deg", "val":3.141592653589793}, "intervals":63, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x + 0.5 m", "val":8.0}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading", "val":0.0}, "intervals":28, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"MaxVelocity", "val":1.3}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":{"exp":"MaxAcceleration", "val":3.0}}}, "enabled":true}, + {"from":"first", "to":1, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"3 rad / s", "val":3.0}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInLane", "props":{"tolerance":{"exp":"0.01 m", "val":0.01}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepOutCircle", "props":{"x":{"exp":"Reef.x", "val":4.491}, "y":{"exp":"Reef.y", "val":4.026}, "r":{"exp":"1 m", "val":1.0}}}, "enabled":true}, + {"from":1, "to":2, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0.5 rad / s", "val":0.5}}}, "enabled":true}, + {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"3 rad / s", "val":3.0}}}, "enabled":true}, + {"from":3, "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0.5 rad / s", "val":0.5}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.75599,2.35446,4.11369,4.71541], + "samples":[ + {"t":0.0, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.99777, "ay":0.0, "alpha":14.15358, "fx":[-0.68121,-1.25895,75.91331,75.9155], "fy":[48.62437,-48.62491,-38.74887,38.74933]}, + {"t":0.02787, "x":7.50116, "y":4.0, "heading":0.0, "vx":0.08356, "vy":0.0, "omega":0.3945, "ax":2.99881, "ay":0.0, "alpha":12.02302, "fx":[5.41048,4.6104,69.95911,69.96034], "fy":[40.91114,-40.92107,-33.66187,33.67167]}, + {"t":0.05575, "x":7.50466, "y":4.0, "heading":0.011, "vx":0.16714, "vy":0.0, "omega":0.72962, "ax":2.99871, "ay":0.0, "alpha":10.13921, "fx":[9.83379,9.80126,65.43052,64.87017], "fy":[33.37953,-34.07431,-28.2593,28.95389]}, + {"t":0.08362, "x":7.51048, "y":4.0, "heading":0.03133, "vx":0.25072, "vy":0.0, "omega":1.01222, "ax":2.99861, "ay":-0.00001, "alpha":8.30593, "fx":[14.28007,15.46732,60.75538,59.4276], "fy":[26.44867,-28.05975,-23.07374,24.68457]}, + {"t":0.11149, "x":7.51864, "y":4.0, "heading":0.05955, "vx":0.3343, "vy":0.0, "omega":1.24373, "ax":2.99848, "ay":-0.00001, "alpha":6.6701, "fx":[18.26138,20.58304,56.56408,54.51554], "fy":[20.41051,-22.87617,-18.27582,20.74116]}, + {"t":0.13936, "x":7.52912, "y":4.0, "heading":0.09421, "vx":0.41788, "vy":0.0, "omega":1.42965, "ax":2.99833, "ay":-0.00001, "alpha":5.26465, "fx":[21.74155,24.93812,52.92056,50.3162], "fy":[15.36489,-18.45609,-14.07003,17.16083]}, + {"t":0.16724, "x":7.54193, "y":4.0, "heading":0.13406, "vx":0.50145, "vy":0.0, "omega":1.57639, "ax":2.99814, "ay":-0.00001, "alpha":4.08534, "fx":[24.7579,28.5348,49.76807,46.84637], "fy":[11.29392,-14.72313,-10.54339,13.97215]}, + {"t":0.19511, "x":7.55707, "y":4.0, "heading":0.178, "vx":0.58502, "vy":0.0, "omega":1.69026, "ax":2.99791, "ay":-0.00001, "alpha":3.22421, "fx":[26.79281,30.71669,47.76359,44.62243], "fy":[8.13104,-11.63446,-7.68072,11.18365]}, + {"t":0.22298, "x":7.57454, "y":4.0, "heading":0.22511, "vx":0.66858, "vy":0.0, "omega":1.78013, "ax":2.99761, "ay":-0.00001, "alpha":2.4536, "fx":[28.92072,33.00162,45.50408,42.45416], "fy":[5.73953,-9.10993,-5.49629,8.86619]}, + {"t":0.25086, "x":7.59434, "y":4.0, "heading":0.27473, "vx":0.75213, "vy":0.0, "omega":1.84852, "ax":2.99721, "ay":-0.00001, "alpha":1.85411, "fx":[30.62772,34.75203,43.6603,40.8206], "fy":[3.98278,-7.091,-3.85735,6.96507]}, + {"t":0.27873, "x":7.61647, "y":4.0, "heading":0.32625, "vx":0.83567, "vy":0.0, "omega":1.9002, "ax":2.99666, "ay":-0.00001, "alpha":1.39132, "fx":[31.95961,36.1318,42.15141,39.58995], "fy":[2.715,-5.48909,-2.65454,5.42818]}, + {"t":0.3066, "x":7.64093, "y":4.0, "heading":0.37922, "vx":0.9192, "vy":0.0, "omega":1.93898, "ax":2.99582, "ay":-0.00001, "alpha":1.03848, "fx":[32.99453,37.18877,40.92949,38.67814], "fy":[1.81442,-4.2275,-1.78839,4.20112]}, + {"t":0.33447, "x":7.66771, "y":4.0, "heading":0.43326, "vx":1.0027, "vy":0.0, "omega":1.96792, "ax":2.99442, "ay":0.0, "alpha":0.76784, "fx":[33.77301,38.06474,39.91092,37.97255], "fy":[1.1817,-3.23282,-1.17303,3.22403]}, + {"t":0.36235, "x":7.69682, "y":4.0, "heading":0.48811, "vx":1.08616, "vy":0.0, "omega":1.98932, "ax":2.99164, "ay":0.00001, "alpha":0.56082, "fx":[34.34244,38.78478,39.0427,37.41198], "fy":[0.74276,-2.44657,-0.74167,2.44577]}, + {"t":0.39022, "x":7.72826, "y":4.0, "heading":0.54356, "vx":1.16955, "vy":0.0, "omega":2.00496, "ax":2.98331, "ay":0.00001, "alpha":0.41212, "fx":[34.87725,38.80402,38.40846,37.07585], "fy":[0.44298,-1.82074,-0.44376,1.82219]}, + {"t":0.41809, "x":7.76202, "y":4.0, "heading":0.59944, "vx":1.2527, "vy":0.0, "omega":2.01644, "ax":1.68007, "ay":-0.00044, "alpha":0.30561, "fx":[19.30605,21.96356,21.89376,20.83992], "fy":[0.23744,-1.32315,-0.24899,1.3128]}, + {"t":0.44597, "x":7.79759, "y":4.0, "heading":0.65565, "vx":1.29953, "vy":-0.00001, "omega":2.02496, "ax":0.00018, "ay":-0.00015, "alpha":0.21624, "fx":[-1.02779,0.29897,0.75882,-0.02111], "fy":[0.11236,-0.90396,-0.11631,0.90051]}, + {"t":0.47384, "x":7.83381, "y":4.0, "heading":0.71209, "vx":1.29953, "vy":-0.00002, "omega":2.03099, "ax":0.0, "ay":0.00003, "alpha":0.13507, "fx":[-0.50014,-0.17467,0.59124,0.0835], "fy":[0.03878,-0.5531,-0.03818,0.55376]}, + {"t":0.50171, "x":7.87003, "y":4.0, "heading":0.7687, "vx":1.29953, "vy":-0.00002, "omega":2.03475, "ax":0.0, "ay":0.00007, "alpha":0.06264, "fx":[-0.27143,0.0522,0.2345,-0.01533], "fy":[0.00416,-0.26071,-0.00229,0.26259]}, + {"t":0.52958, "x":7.90625, "y":4.0, "heading":0.82541, "vx":1.29953, "vy":-0.00002, "omega":2.0365, "ax":0.0, "ay":0.00008, "alpha":0.00257, "fx":[-0.03831,0.10394,-0.0308,-0.03489], "fy":[0.00004,-0.01358,0.00188,0.0155]}, + {"t":0.55746, "x":7.94247, "y":4.0, "heading":0.88218, "vx":1.29953, "vy":-0.00001, "omega":2.03657, "ax":0.0, "ay":0.00006, "alpha":-0.04894, "fx":[0.17465,0.08497,-0.24529,-0.01439], "fy":[0.02018,0.19732,-0.01857,-0.19571]}, + {"t":0.58533, "x":7.97869, "y":4.0, "heading":0.93894, "vx":1.29953, "vy":-0.00001, "omega":2.03521, "ax":0.0, "ay":0.00005, "alpha":-0.0937, "fx":[0.35559,0.05203,-0.43169,0.02401], "fy":[0.05985,0.37813,-0.05857,-0.37683]}, + {"t":0.6132, "x":8.01492, "y":4.0, "heading":0.99567, "vx":1.29953, "vy":-0.00001, "omega":2.03259, "ax":0.0, "ay":0.00004, "alpha":-0.1324, "fx":[0.50555,0.01224,-0.59297,0.07512], "fy":[0.11494,0.53116,-0.11387,-0.53008]}, + {"t":0.64108, "x":8.05114, "y":4.0, "heading":1.05232, "vx":1.29953, "vy":-0.00001, "omega":2.0289, "ax":0.0, "ay":0.00004, "alpha":-0.16537, "fx":[0.62673,-0.03566,-0.72776,0.13664], "fy":[0.18147,0.65713,-0.18046,-0.6561]}, + {"t":0.66895, "x":8.08736, "y":4.0, "heading":1.10887, "vx":1.29953, "vy":-0.00001, "omega":2.02429, "ax":0.0, "ay":0.00005, "alpha":-0.19223, "fx":[0.71826,-0.09058,-0.83271,0.20497], "fy":[0.2548,0.75416,-0.25364,-0.75296]}, + {"t":0.69682, "x":8.12358, "y":4.0, "heading":1.1653, "vx":1.29953, "vy":-0.00001, "omega":2.01894, "ax":0.0, "ay":0.00006, "alpha":-0.21211, "fx":[0.77724,-0.14823,-0.90378,0.27471], "fy":[0.32916,0.81903,-0.3276,-0.8174]}, + {"t":0.72469, "x":8.1598, "y":4.0, "heading":1.22157, "vx":1.29953, "vy":0.0, "omega":2.01302, "ax":0.0, "ay":0.00009, "alpha":-0.22326, "fx":[0.79804,-0.20105,-0.93491,0.33786], "fy":[0.39664,0.84611,-0.39441,-0.84378]}, + {"t":0.75257, "x":8.19602, "y":4.0, "heading":1.27768, "vx":1.29953, "vy":0.0, "omega":2.0068, "ax":0.0, "ay":0.00013, "alpha":-0.22299, "fx":[0.77279,-0.23793,-0.91804,0.38312], "fy":[0.44621,0.82765,-0.44306,-0.8244]}, + {"t":0.78044, "x":8.23225, "y":4.0, "heading":1.33361, "vx":1.29953, "vy":0.0, "omega":2.00059, "ax":0.0, "ay":0.00017, "alpha":-0.20724, "fx":[0.69067,-0.24301,-0.8421,0.39439], "fy":[0.46201,0.7529,-0.45788,-0.74866]}, + {"t":0.80831, "x":8.26847, "y":4.0, "heading":1.38938, "vx":1.29953, "vy":0.00001, "omega":1.99481, "ax":0.0, "ay":0.00019, "alpha":-0.17009, "fx":[0.5374,-0.19353,-0.6924,0.34848], "fy":[0.42107,0.60743,-0.41631,-0.6026]}, + {"t":0.83619, "x":8.30469, "y":4.0, "heading":1.44498, "vx":1.29953, "vy":0.00001, "omega":1.99007, "ax":0.0, "ay":0.00016, "alpha":-0.10302, "fx":[0.29449,-0.05677,-0.44977,0.21199], "fy":[0.28997,0.37228,-0.28586,-0.36815]}, + {"t":0.86406, "x":8.34091, "y":4.0, "heading":1.50045, "vx":1.29953, "vy":0.00002, "omega":1.9872, "ax":0.0, "ay":0.00007, "alpha":-0.01639, "fx":[0.00856,0.15558,-0.16186,-0.00233], "fy":[0.08104,0.09279,-0.07923,-0.09098]}, + {"t":0.89193, "x":8.37713, "y":4.0, "heading":1.55583, "vx":1.29953, "vy":0.00002, "omega":1.98674, "ax":0.0, "ay":-0.00005, "alpha":0.07169, "fx":[-0.25578,0.40138,0.10514,-0.25079], "fy":[-0.16206,-0.1668,0.16086,0.16562]}, + {"t":0.9198, "x":8.41335, "y":4.0, "heading":1.61121, "vx":1.29953, "vy":0.00002, "omega":1.98874, "ax":0.0, "ay":-0.00015, "alpha":0.14343, "fx":[-0.44582,0.627,0.29665,-0.47788], "fy":[-0.38385,-0.35362,0.3801,0.34994]}, + {"t":0.94768, "x":8.44958, "y":4.0, "heading":1.66664, "vx":1.29953, "vy":0.00001, "omega":1.99274, "ax":0.0, "ay":-0.00018, "alpha":0.18269, "fx":[-0.52566,0.77259,0.37543,-0.62241], "fy":[-0.52298,-0.43097,0.51834,0.42646]}, + {"t":0.97555, "x":8.4858, "y":4.0, "heading":1.72219, "vx":1.29953, "vy":0.00001, "omega":1.99783, "ax":0.0, "ay":-0.00016, "alpha":0.19927, "fx":[-0.5352,0.8546,0.38166,-0.7011], "fy":[-0.59608,-0.43813,0.59211,0.43432]}, + {"t":1.00342, "x":8.52202, "y":4.0, "heading":1.77787, "vx":1.29953, "vy":0.0, "omega":2.00338, "ax":0.0, "ay":-0.00011, "alpha":0.20004, "fx":[-0.502,0.88621,0.34319,-0.72744], "fy":[-0.61706,-0.40272,0.61423,0.40005]}, + {"t":1.0313, "x":8.55824, "y":4.0, "heading":1.83371, "vx":1.29953, "vy":0.0, "omega":2.00896, "ax":0.0, "ay":-0.00007, "alpha":0.18973, "fx":[-0.44498,0.87778,0.27924,-0.71209], "fy":[-0.59673,-0.34356,0.595,0.34198]}, + {"t":1.05917, "x":8.59446, "y":4.0, "heading":1.88971, "vx":1.29953, "vy":0.0, "omega":2.01425, "ax":0.0, "ay":-0.00003, "alpha":0.17163, "fx":[-0.37715,0.83734,0.20309,-0.66333], "fy":[-0.54338,-0.27355,0.54252,0.27282]}, + {"t":1.08704, "x":8.63068, "y":4.0, "heading":1.94585, "vx":1.29953, "vy":0.0, "omega":2.01903, "ax":0.0, "ay":-0.00001, "alpha":0.14791, "fx":[-0.30743,0.77086,0.12393,-0.58741], "fy":[-0.46322,-0.20144,0.46297,0.20129]}, + {"t":1.11491, "x":8.66691, "y":4.0, "heading":2.00213, "vx":1.29953, "vy":0.0, "omega":2.02315, "ax":0.0, "ay":0.00001, "alpha":0.11994, "fx":[-0.24189,0.68257,0.04811,-0.48884], "fy":[-0.36067,-0.13324,0.3608,0.13344]}, + {"t":1.14279, "x":8.70313, "y":4.0, "heading":2.05852, "vx":1.29953, "vy":0.0, "omega":2.0265, "ax":0.0, "ay":0.00001, "alpha":0.08845, "fx":[-0.18472,0.57506,-0.01991,-0.37048], "fy":[-0.23858,-0.0731,0.2389,0.07346]}, + {"t":1.17066, "x":8.73935, "y":4.0, "heading":2.115, "vx":1.29953, "vy":0.0, "omega":2.02896, "ax":0.0, "ay":0.00002, "alpha":0.05366, "fx":[-0.13888,0.44931,-0.07684,-0.23363], "fy":[-0.09819,-0.02402,0.09858,0.02443]}, + {"t":1.19853, "x":8.77557, "y":4.0, "heading":2.17155, "vx":1.29953, "vy":0.0, "omega":2.03046, "ax":0.0, "ay":0.00002, "alpha":0.01523, "fx":[-0.1067,0.30454,-0.12001,-0.07787], "fy":[0.06088,0.01159,-0.06049,-0.01121]}, + {"t":1.2264, "x":8.81179, "y":4.0, "heading":2.22815, "vx":1.29953, "vy":0.0, "omega":2.03088, "ax":0.0, "ay":0.00001, "alpha":-0.0277, "fx":[-0.09031,0.13785,-0.14682,0.09924], "fy":[0.24103,0.03141,-0.2407,-0.03109]}, + {"t":1.25428, "x":8.84801, "y":4.0, "heading":2.28475, "vx":1.29953, "vy":0.0, "omega":2.03011, "ax":0.0, "ay":0.00001, "alpha":-0.07669, "fx":[-0.09226,-0.05626,-0.15416,0.30263], "fy":[0.44711,0.03262,-0.44686,-0.03237]}, + {"t":1.28215, "x":8.88424, "y":4.0, "heading":2.34134, "vx":1.29953, "vy":0.0, "omega":2.02797, "ax":0.0, "ay":0.00001, "alpha":-0.13418, "fx":[-0.11617,-0.28681,-0.13767,0.5406], "fy":[0.68729,0.01119,-0.6871,-0.011]}, + {"t":1.31002, "x":8.92046, "y":4.0, "heading":2.39786, "vx":1.29953, "vy":0.0, "omega":2.02423, "ax":0.0, "ay":0.00001, "alpha":-0.20377, "fx":[-0.16772,-0.56733,-0.0907,0.82571], "fy":[0.97396,-0.03914,-0.97383,0.03927]}, + {"t":1.3379, "x":8.95668, "y":4.0, "heading":2.45429, "vx":1.29953, "vy":0.0, "omega":2.01855, "ax":0.0, "ay":0.0, "alpha":-0.29076, "fx":[-0.25604,-0.91764,-0.00285,1.17649], "fy":[1.32547,-0.1283,-1.32535,0.1284]}, + {"t":1.36577, "x":8.9929, "y":4.0, "heading":2.51055, "vx":1.29953, "vy":0.0, "omega":2.01045, "ax":0.0, "ay":0.00001, "alpha":-0.40264, "fx":[-0.39569,-1.36547,0.14215,1.61897], "fy":[1.76763,-0.27202,-1.76746,0.27212]}, + {"t":1.39364, "x":9.02912, "y":4.0, "heading":2.56659, "vx":1.29953, "vy":0.0, "omega":1.99923, "ax":0.0, "ay":0.00001, "alpha":-0.55003, "fx":[-0.60956,-1.9491,0.36936,2.18926], "fy":[2.33627,-0.49475,-2.33596,0.49489]}, + {"t":1.42151, "x":9.06534, "y":4.0, "heading":2.62231, "vx":1.29953, "vy":0.0, "omega":1.98389, "ax":0.0, "ay":0.00002, "alpha":-0.7476, "fx":[-0.93263,-2.71967,0.71664,2.93563], "fy":[3.07936,-0.83374,-3.07882,0.83397]}, + {"t":1.44939, "x":9.10157, "y":4.0, "heading":2.67761, "vx":1.29953, "vy":0.0, "omega":1.96306, "ax":0.0, "ay":0.00003, "alpha":-1.01529, "fx":[-1.41712,-3.7438,1.23978,3.9211], "fy":[4.05951,-1.34414,-4.05864,1.34455]}, + {"t":1.47726, "x":9.13779, "y":4.0, "heading":2.73232, "vx":1.29953, "vy":0.0, "omega":1.93476, "ax":0.0, "ay":0.00004, "alpha":-1.37951, "fx":[-2.13822,-5.1049,2.01843,5.22465], "fy":[5.35505,-2.10505,-5.35386,2.10583]}, + {"t":1.50513, "x":9.17401, "y":4.0, "heading":2.78625, "vx":1.29953, "vy":0.0, "omega":1.89631, "ax":0.0, "ay":0.00005, "alpha":-1.87393, "fx":[-3.19997,-6.90238,3.16188,6.94044], "fy":[7.05886,-3.22519,-7.05775,3.22678]}, + {"t":1.53301, "x":9.21023, "y":4.0, "heading":2.83911, "vx":1.29953, "vy":0.0, "omega":1.84408, "ax":0.0, "ay":0.00007, "alpha":-2.53927, "fx":[-4.73892,-9.24653,4.81244,9.17297], "fy":[9.27289,-4.84595,-9.27313,4.84951]}, + {"t":1.56088, "x":9.24645, "y":4.0, "heading":2.8905, "vx":1.29953, "vy":0.00001, "omega":1.7733, "ax":0.0, "ay":0.00007, "alpha":-3.42102, "fx":[-6.92151,-12.24647,7.14226,12.02567], "fy":[12.09543,-7.13706,-12.10032,7.14539]}, + {"t":1.58875, "x":9.28267, "y":4.0, "heading":2.93993, "vx":1.29953, "vy":0.00001, "omega":1.67795, "ax":0.0, "ay":0.00005, "alpha":-4.56385, "fx":[-9.9304,-15.98984,10.33804,15.58216], "fy":[15.60062,-10.27896,-15.61724,10.29819]}, + {"t":1.61662, "x":9.3189, "y":4.0, "heading":2.9867, "vx":1.29953, "vy":0.00001, "omega":1.55074, "ax":0.0, "ay":0.00001, "alpha":-6.00166, "fx":[-13.9338,-20.51398,14.56736,19.88038], "fy":[19.81124,-14.42547,-19.85283,14.46758]}, + {"t":1.6445, "x":9.35512, "y":4.0, "heading":3.02992, "vx":1.29953, "vy":0.00001, "omega":1.38345, "ax":0.0, "ay":-0.00005, "alpha":-7.74453, "fx":[-19.03811,-25.77576,19.92607,24.88776], "fy":[24.67434,-19.6473,-24.76215,19.7325]}, + {"t":1.67237, "x":9.39134, "y":4.0, "heading":3.06848, "vx":1.29953, "vy":0.00001, "omega":1.16759, "ax":0.0, "ay":-0.0001, "alpha":-9.77055, "fx":[-25.24388,-31.64768,26.38626,30.50526], "fy":[30.06969,-25.88197,-30.23173,26.0391]}, + {"t":1.70024, "x":9.42756, "y":4.0, "heading":3.10103, "vx":1.29953, "vy":0.00001, "omega":0.89526, "ax":0.0, "ay":-0.00001, "alpha":-12.0264, "fx":[-32.40348,-37.97252,33.7715,36.60441], "fy":[35.84782,-32.90698,-36.11368,33.17255]}, + {"t":1.72812, "x":9.46378, "y":4.0, "heading":3.12598, "vx":1.29953, "vy":0.00001, "omega":0.56005, "ax":-0.01306, "ay":0.0007, "alpha":-14.47408, "fx":[-40.48868,-45.30276,41.93037,43.2081], "fy":[41.74946,-40.20232,-42.24192,40.72985]}, + {"t":1.75599, "x":9.5, "y":4.0, "heading":3.14159, "vx":1.29917, "vy":0.00002, "omega":0.15662, "ax":0.01296, "ay":-0.00053, "alpha":-3.51865, "fx":[-10.07568,-10.07491,10.40028,10.39845], "fy":[10.20739,-10.47743,-9.89663,10.13998]}, + {"t":1.79119, "x":9.54574, "y":4.0, "heading":-3.13608, "vx":1.29963, "vy":0.00001, "omega":0.03275, "ax":0.0, "ay":-0.00023, "alpha":-1.10705, "fx":[-3.24197,-3.21096,3.24195,3.211], "fy":[3.18088,-3.28423,-3.11573,3.20783]}, + {"t":1.8264, "x":9.5915, "y":4.0, "heading":-3.13493, "vx":1.29963, "vy":0.0, "omega":-0.00623, "ax":0.0, "ay":0.0, "alpha":-0.35819, "fx":[-1.05042,-1.03843,1.05041,1.03842], "fy":[1.02815,-1.04966,-1.01818,1.03992]}, + {"t":1.8616, "x":9.63725, "y":4.0, "heading":-3.13515, "vx":1.29963, "vy":0.0, "omega":-0.01884, "ax":-0.00003, "ay":0.00006, "alpha":-0.12147, "fx":[-0.35602,-0.35216,0.35538,0.35152], "fy":[0.34999,-0.34623,-0.35442,0.35384]}, + {"t":1.8968, "x":9.683, "y":4.0, "heading":-3.13581, "vx":1.29962, "vy":0.0, "omega":-0.02311, "ax":-0.67383, "ay":-0.00004, "alpha":-0.04333, "fx":[-8.54922,-8.54803,-8.29642,-8.29761], "fy":[0.12458,-0.11732,-0.13488,0.12581]}, + {"t":1.93201, "x":9.72833, "y":4.0, "heading":-3.13662, "vx":1.2759, "vy":0.0, "omega":-0.02464, "ax":-2.98922, "ay":0.0, "alpha":-0.01555, "fx":[-37.41002,-37.40967,-37.3205,-37.32084], "fy":[0.04544,-0.03847,-0.0528,0.04583]}, + {"t":1.96721, "x":9.7714, "y":4.0, "heading":-3.13749, "vx":1.17067, "vy":0.0, "omega":-0.02519, "ax":-2.99464, "ay":0.0, "alpha":-0.00475, "fx":[-37.44707,-37.44698,-37.41889,-37.41897], "fy":[0.01351,-0.00855,-0.01851,0.01361]}, + {"t":2.00242, "x":9.81076, "y":4.0, "heading":-3.13838, "vx":1.06525, "vy":0.0, "omega":-0.02535, "ax":-2.99643, "ay":0.0, "alpha":0.00042, "fx":[-37.4553,-37.4553,-37.45553,-37.45553], "fy":[-0.00236,0.00483,-0.0002,-0.00236]}, + {"t":2.03762, "x":9.8464, "y":4.0, "heading":-3.13927, "vx":0.95976, "vy":0.0, "omega":-0.02534, "ax":-2.99733, "ay":0.0, "alpha":0.00401, "fx":[-37.4569,-37.45694,-37.4763,-37.47626], "fy":[-0.01359,0.01338,0.01374,-0.01364]}, + {"t":2.07282, "x":9.87833, "y":4.0, "heading":-3.14016, "vx":0.85424, "vy":0.0, "omega":-0.0252, "ax":-2.99786, "ay":0.0, "alpha":0.00837, "fx":[-37.45176,-37.45184,-37.49484,-37.49477], "fy":[-0.02706,0.02408,0.03003,-0.02715]}, + {"t":2.10803, "x":9.90654, "y":4.0, "heading":-3.14105, "vx":0.74871, "vy":0.0, "omega":-0.0249, "ax":-2.99822, "ay":0.0, "alpha":0.01668, "fx":[-37.43325,-37.43335,-37.52228,-37.52218], "fy":[-0.0523,0.04707,0.05753,-0.0524]}, + {"t":2.14323, "x":9.93104, "y":4.0, "heading":3.14126, "vx":0.64316, "vy":0.0, "omega":-0.02432, "ax":-2.99848, "ay":0.0, "alpha":0.03626, "fx":[-37.38186,-37.38192,-37.58004,-37.57997], "fy":[-0.11135,0.10482,0.11781,-0.11137]}, + {"t":2.17844, "x":9.95183, "y":4.0, "heading":3.1404, "vx":0.5376, "vy":0.0, "omega":-0.02304, "ax":-2.99867, "ay":0.0, "alpha":0.0874, "fx":[-37.24207,-37.24178,-37.7246,-37.72488], "fy":[-0.26603,0.26088,0.27057,-0.2655]}, + {"t":2.21364, "x":9.9689, "y":4.0, "heading":3.13959, "vx":0.43203, "vy":0.0, "omega":-0.01996, "ax":-2.99882, "ay":0.0, "alpha":0.23, "fx":[-36.84966,-36.8478,-38.12074,-38.12256], "fy":[-0.69996,0.70319,0.69306,-0.69638]}, + {"t":2.24884, "x":9.98225, "y":4.0, "heading":3.13889, "vx":0.32646, "vy":0.0, "omega":-0.01187, "ax":-2.99893, "ay":0.0, "alpha":0.64638, "fx":[-35.70572,-35.69777,-39.26789,-39.27532], "fy":[-1.97725,2.00848,1.92325,-1.95458]}, + {"t":2.28405, "x":9.99188, "y":4.0, "heading":3.13847, "vx":0.22089, "vy":0.0, "omega":0.01089, "ax":-2.99903, "ay":0.0, "alpha":1.89861, "fx":[-32.2762,-32.24663,-42.70231,-42.72641], "fy":[-5.87441,5.99267,5.58884,-5.70719]}, + {"t":2.31925, "x":9.9978, "y":4.0, "heading":3.13886, "vx":0.11531, "vy":0.0, "omega":0.07773, "ax":-2.99911, "ay":0.0, "alpha":5.71172, "fx":[-21.89757,-21.80418,-53.10688,-53.14696], "fy":[-18.21724,18.63162,16.38039,-16.79485]}, + {"t":2.35446, "x":10.0, "y":4.0, "heading":3.14159, "vx":0.00973, "vy":0.0, "omega":0.2788, "ax":-2.99778, "ay":0.0, "alpha":12.78152, "fx":[-2.3039,-2.63127,-72.47708,-72.47669], "fy":[-43.10633,43.10543,35.2201,-35.2193]}, + {"t":2.38238, "x":9.9991, "y":4.0, "heading":-3.13381, "vx":-0.07398, "vy":0.0, "omega":0.63572, "ax":-2.99881, "ay":0.0, "alpha":10.66222, "fx":[-8.33975,-8.53532,-66.7272,-66.33822], "fy":[-35.36089,35.83329,29.80874,-30.28127]}, + {"t":2.41031, "x":9.99587, "y":4.0, "heading":-3.11606, "vx":-0.15772, "vy":0.0, "omega":0.93345, "ax":-2.99872, "ay":0.0, "alpha":8.72864, "fx":[-13.15042,-14.49455,-61.69768,-60.59327], "fy":[-28.12927,29.45198,24.49244,-25.81531]}, + {"t":2.43823, "x":9.99029, "y":4.0, "heading":-3.08999, "vx":-0.24146, "vy":0.0, "omega":1.17719, "ax":-2.99861, "ay":0.0, "alpha":6.98529, "fx":[-17.45124,-19.93893,-57.18356,-55.35684], "fy":[-21.72923,23.91735,19.45822,-21.64654]}, + {"t":2.46615, "x":9.98238, "y":4.0, "heading":-3.05712, "vx":-0.32519, "vy":0.0, "omega":1.37225, "ax":-2.99849, "ay":0.0, "alpha":5.47897, "fx":[-21.21136,-24.59858,-53.26895,-50.84538], "fy":[-16.33491,19.1894,14.98378,-17.83851]}, + {"t":2.49408, "x":9.97213, "y":4.0, "heading":-3.0188, "vx":-0.40892, "vy":0.0, "omega":1.52525, "ax":-2.99833, "ay":0.0, "alpha":4.29488, "fx":[-24.01367,-27.84195,-49.6318,-48.42927], "fy":[-12.01067,15.21048,11.20333,-14.40338]}, + {"t":2.522, "x":9.95955, "y":4.0, "heading":-2.97621, "vx":-0.49265, "vy":0.0, "omega":1.64518, "ax":-2.99815, "ay":-0.00001, "alpha":3.34647, "fx":[-26.38959,-30.4446,-48.05386,-45.01937], "fy":[-8.60914,11.95856,8.14547,-11.49518]}, + {"t":2.54993, "x":9.94462, "y":4.0, "heading":-2.93027, "vx":-0.57637, "vy":0.0, "omega":1.73863, "ax":-2.99792, "ay":-0.00001, "alpha":2.53042, "fx":[-28.66803,-32.83813,-45.67489,-42.71481], "fy":[-6.0662,9.31192,5.81979,-9.06583]}, + {"t":2.57785, "x":9.92736, "y":4.0, "heading":-2.88172, "vx":-0.66008, "vy":0.0, "omega":1.80929, "ax":-2.99762, "ay":-0.00001, "alpha":1.89896, "fx":[-30.49217,-34.64707,-43.74921,-40.99253], "fy":[-4.20361,7.20698,4.07803,-7.08172]}, + {"t":2.60578, "x":9.90775, "y":4.0, "heading":-2.83119, "vx":-0.74379, "vy":0.0, "omega":1.86232, "ax":-2.99722, "ay":-0.00001, "alpha":1.41812, "fx":[-31.9432,-35.96364,-42.21656,-39.73775], "fy":[-2.86594,5.55105,2.80515,-5.4906]}, + {"t":2.6337, "x":9.88582, "y":4.0, "heading":-2.77919, "vx":-0.82749, "vy":0.0, "omega":1.90192, "ax":-2.99667, "ay":-0.00001, "alpha":1.05315, "fx":[-33.07313,-36.94755,-40.99039,-38.8223], "fy":[-1.91821,4.25316,1.89103,-4.22632]}, + {"t":2.66162, "x":9.86154, "y":4.0, "heading":-2.72608, "vx":-0.91117, "vy":0.0, "omega":1.93132, "ax":-2.99583, "ay":-0.00001, "alpha":0.77956, "fx":[-33.96858,-37.61272,-40.03124,-38.1792], "fy":[-1.25585,3.24054,1.24507,-3.23008]}, + {"t":2.68955, "x":9.83493, "y":4.0, "heading":-2.67215, "vx":-0.99482, "vy":0.0, "omega":1.95309, "ax":-2.99445, "ay":-0.00001, "alpha":0.57186, "fx":[-34.64438,-38.13138,-39.24738,-37.69927], "fy":[-0.79762,2.44753,0.79449,-2.44467]}, + {"t":2.71747, "x":9.80598, "y":4.0, "heading":-2.61761, "vx":-1.07844, "vy":0.0, "omega":1.96906, "ax":-2.99168, "ay":0.0, "alpha":0.41526, "fx":[-35.15605,-38.47961,-38.60621,-37.34207], "fy":[-0.48512,1.82473,0.48517,-1.82497]}, + {"t":2.7454, "x":9.7747, "y":4.0, "heading":-2.56262, "vx":-1.16198, "vy":0.0, "omega":1.98066, "ax":-2.98342, "ay":0.0, "alpha":0.30038, "fx":[-35.55063,-38.45012,-38.08704,-37.08316], "fy":[-0.2767,1.33496,0.27741,-1.33585]}, + {"t":2.77332, "x":9.74109, "y":4.0, "heading":-2.50732, "vx":-1.24529, "vy":0.0, "omega":1.98905, "ax":-1.94238, "ay":-0.00009, "alpha":0.23148, "fx":[-23.45682,-23.89675,-25.267,-24.49819], "fy":[-0.14335,0.94781,0.14132,-0.95005]}, + {"t":2.80125, "x":9.70556, "y":4.0, "heading":-2.45177, "vx":-1.29953, "vy":-0.00001, "omega":1.99551, "ax":-0.00021, "ay":-0.00002, "alpha":0.15891, "fx":[0.47312,0.49928,-0.77417,-0.20882], "fy":[-0.06061,0.64636,0.06013,-0.64699]}, + {"t":2.82917, "x":9.66927, "y":4.0, "heading":-2.39605, "vx":-1.29954, "vy":-0.00001, "omega":1.99995, "ax":0.0, "ay":0.0, "alpha":0.0999, "fx":[-0.06513,1.35765,-0.8306,-0.46197], "fy":[-0.01477,0.40086,0.01479,-0.40079]}, + {"t":2.85709, "x":9.63298, "y":4.0, "heading":-2.3402, "vx":-1.29954, "vy":-0.00001, "omega":2.00274, "ax":0.0, "ay":0.00001, "alpha":0.04596, "fx":[-0.15229,1.0093,-0.52305,-0.33399], "fy":[0.00434,0.20269,-0.00398,-0.20237]}, + {"t":2.88502, "x":9.59669, "y":4.0, "heading":-2.28428, "vx":-1.29954, "vy":-0.00001, "omega":2.00402, "ax":0.0, "ay":0.00001, "alpha":0.00259, "fx":[-0.27909,0.90224,-0.32381,-0.29938], "fy":[0.00402,0.04204,-0.00362,-0.04182]}, + {"t":2.91294, "x":9.56041, "y":4.0, "heading":-2.22832, "vx":-1.29954, "vy":-0.00001, "omega":2.00409, "ax":0.0, "ay":0.0, "alpha":-0.03946, "fx":[-0.56719,1.371,-0.33714,-0.46671], "fy":[-0.01088,-0.09196,0.01112,0.09181]}, + {"t":2.94087, "x":9.52412, "y":4.0, "heading":-2.17235, "vx":-1.29954, "vy":-0.00001, "omega":2.00299, "ax":0.0, "ay":0.0, "alpha":-0.07331, "fx":[-0.64803,1.28128,-0.17711,-0.45617], "fy":[-0.03773,-0.20804,0.03781,0.20783]}, + {"t":2.96879, "x":9.48783, "y":4.0, "heading":-2.11642, "vx":-1.29954, "vy":-0.00001, "omega":2.00094, "ax":0.0, "ay":0.0, "alpha":-0.10166, "fx":[-0.68147,1.09989,0.00394,-0.4224], "fy":[-0.07521,-0.31176,0.07519,0.3116]}, + {"t":2.99672, "x":9.45154, "y":4.0, "heading":-2.06055, "vx":-1.29954, "vy":-0.00001, "omega":1.9981, "ax":0.0, "ay":0.0, "alpha":-0.1256, "fx":[-0.70283,0.93471,0.16794,-0.39985], "fy":[-0.12128,-0.40188,0.12128,0.40189]}, + {"t":3.02464, "x":9.41525, "y":4.0, "heading":-2.00475, "vx":-1.29954, "vy":-0.00001, "omega":1.9946, "ax":0.0, "ay":0.00001, "alpha":-0.14542, "fx":[-0.71865,0.81135,0.30234,-0.39508], "fy":[-0.17313,-0.47573,0.17334,0.47604]}, + {"t":3.05256, "x":9.37896, "y":4.0, "heading":-1.94905, "vx":-1.29954, "vy":-0.00001, "omega":1.99054, "ax":0.0, "ay":0.00003, "alpha":-0.16025, "fx":[-0.72437,0.72771,0.40067,-0.40405], "fy":[-0.22598,-0.52756,0.2266,0.52834]}, + {"t":3.08049, "x":9.34267, "y":4.0, "heading":-1.89347, "vx":-1.29954, "vy":0.0, "omega":1.98606, "ax":0.0, "ay":0.00005, "alpha":-0.16826, "fx":[-0.71102,0.67193,0.45693,-0.41788], "fy":[-0.2727,-0.55017,0.27395,0.55159]}, + {"t":3.10841, "x":9.30639, "y":4.0, "heading":-1.83801, "vx":-1.29954, "vy":0.0, "omega":1.98136, "ax":0.0, "ay":0.00008, "alpha":-0.16666, "fx":[-0.66762,0.62717,0.46417,-0.42375], "fy":[-0.30283,-0.53452,0.30489,0.53672]}, + {"t":3.13634, "x":9.2701, "y":4.0, "heading":-1.78268, "vx":-1.29954, "vy":0.0, "omega":1.97671, "ax":0.0, "ay":0.00012, "alpha":-0.15131, "fx":[-0.58057,0.57222,0.41241,-0.4041], "fy":[-0.30125,-0.46937,0.30414,0.47235]}, + {"t":3.16426, "x":9.23381, "y":4.0, "heading":-1.72748, "vx":-1.29954, "vy":0.0, "omega":1.97248, "ax":0.0, "ay":0.00014, "alpha":-0.11632, "fx":[-0.43409,0.48025,0.28859,-0.33479], "fy":[-0.24608,-0.34068,0.24946,0.34411]}, + {"t":3.19219, "x":9.19752, "y":4.0, "heading":-1.6724, "vx":-1.29954, "vy":0.00001, "omega":1.96924, "ax":0.0, "ay":0.00011, "alpha":-0.0535, "fx":[-0.20941,0.31626,0.07572,-0.1826], "fy":[-0.10622,-0.13145,0.10898,0.13422]}, + {"t":3.22011, "x":9.16123, "y":4.0, "heading":-1.61741, "vx":-1.29954, "vy":0.00001, "omega":1.96774, "ax":0.0, "ay":0.00003, "alpha":0.02526, "fx":[0.04407,0.0948,-0.17331,0.0344], "fy":[0.09951,0.10933,-0.09869,-0.1085]}, + {"t":3.24803, "x":9.12494, "y":4.0, "heading":-1.56247, "vx":-1.29954, "vy":0.00001, "omega":1.96845, "ax":0.0, "ay":-0.00006, "alpha":0.10012, "fx":[0.26014,-0.13659,-0.38845,0.26486], "fy":[0.32042,0.31606,-0.32193,-0.31755]}, + {"t":3.27596, "x":9.08865, "y":4.0, "heading":-1.5075, "vx":-1.29954, "vy":0.00001, "omega":1.97124, "ax":0.0, "ay":-0.00012, "alpha":0.15114, "fx":[0.38437,-0.31639,-0.51172,0.44371], "fy":[0.49225,0.4349,-0.49522,-0.43781]}, + {"t":3.30388, "x":9.05236, "y":4.0, "heading":-1.45245, "vx":-1.29954, "vy":0.00001, "omega":1.97546, "ax":0.0, "ay":-0.00012, "alpha":0.17831, "fx":[0.42817,-0.43286,-0.55393,0.55858], "fy":[0.60255,0.47601,-0.60564,-0.47903]}, + {"t":3.33181, "x":9.01608, "y":4.0, "heading":-1.39729, "vx":-1.29954, "vy":0.0, "omega":1.98044, "ax":0.0, "ay":-0.0001, "alpha":0.18849, "fx":[0.41958,-0.49814,-0.54309,0.62161], "fy":[0.6625,0.46654,-0.665,-0.46898]}, + {"t":3.35973, "x":8.97979, "y":4.0, "heading":-1.34199, "vx":-1.29954, "vy":0.0, "omega":1.98571, "ax":0.0, "ay":-0.00007, "alpha":0.18633, "fx":[0.37855,-0.52132,-0.49889,0.64162], "fy":[0.68055,0.4252,-0.68228,-0.42687]}, + {"t":3.38766, "x":8.9435, "y":4.0, "heading":-1.28654, "vx":-1.29954, "vy":0.0, "omega":1.99091, "ax":0.0, "ay":-0.00004, "alpha":0.17507, "fx":[0.31841,-0.50941,-0.4348,0.62576], "fy":[0.66334,0.36518,-0.66439,-0.36618]}, + {"t":3.41558, "x":8.90721, "y":4.0, "heading":-1.23094, "vx":-1.29954, "vy":0.0, "omega":1.9958, "ax":0.0, "ay":-0.00002, "alpha":0.15689, "fx":[0.24939,-0.46754,-0.36106,0.57917], "fy":[0.6159,0.29594,-0.61643,-0.29644]}, + {"t":3.4435, "x":8.87092, "y":4.0, "heading":-1.17521, "vx":-1.29954, "vy":0.0, "omega":2.00018, "ax":0.0, "ay":-0.00001, "alpha":0.13312, "fx":[0.178,-0.39912,-0.28433,0.50541], "fy":[0.5416,0.2242,-0.54177,-0.22435]}, + {"t":3.47143, "x":8.83463, "y":4.0, "heading":-1.11936, "vx":-1.29954, "vy":0.0, "omega":2.0039, "ax":0.0, "ay":0.0, "alpha":0.10461, "fx":[0.10977,-0.30638,-0.2103,0.40686], "fy":[0.44272,0.15507,-0.44268,-0.15502]}, + {"t":3.49935, "x":8.79834, "y":4.0, "heading":-1.0634, "vx":-1.29954, "vy":0.0, "omega":2.00682, "ax":0.0, "ay":0.00001, "alpha":0.07152, "fx":[0.04838,-0.18979,-0.14277,0.28414], "fy":[0.31982,0.09239,-0.31967,-0.09224]}, + {"t":3.52728, "x":8.76206, "y":4.0, "heading":-1.00736, "vx":-1.29954, "vy":0.0, "omega":2.00881, "ax":0.0, "ay":0.00001, "alpha":0.03382, "fx":[-0.00267,-0.04926,-0.08556,0.13744], "fy":[0.17293,0.03966,-0.17276,-0.03948]}, + {"t":3.5552, "x":8.72577, "y":4.0, "heading":-0.95127, "vx":-1.29954, "vy":0.0, "omega":2.00976, "ax":0.0, "ay":0.00001, "alpha":-0.00935, "fx":[-0.04035,0.11812,-0.04178,-0.03604], "fy":[-0.0007,-0.00013,0.00085,0.00028]}, + {"t":3.58313, "x":8.68948, "y":4.0, "heading":-0.89515, "vx":-1.29954, "vy":0.0, "omega":2.0095, "ax":0.0, "ay":0.0, "alpha":-0.05879, "fx":[-0.06131,0.31497,-0.01527,-0.23844], "fy":[-0.20351,-0.02325,0.2036,0.02334]}, + {"t":3.61105, "x":8.65319, "y":4.0, "heading":-0.83903, "vx":-1.29954, "vy":0.0, "omega":2.00786, "ax":0.0, "ay":0.0, "alpha":-0.11672, "fx":[-0.06137,0.54918,-0.01031,-0.47754], "fy":[-0.44315,-0.02562,0.44314,0.02562]}, + {"t":3.63897, "x":8.6169, "y":4.0, "heading":-0.78296, "vx":-1.29954, "vy":0.0, "omega":2.0046, "ax":0.0, "ay":0.0, "alpha":-0.18518, "fx":[-0.03533,0.82759,-0.03288,-0.75943], "fy":[-0.7262,-0.00128,0.72609,0.00117]}, + {"t":3.6669, "x":8.58061, "y":4.0, "heading":-0.72699, "vx":-1.29954, "vy":0.0, "omega":1.99943, "ax":0.0, "ay":-0.00001, "alpha":-0.2685, "fx":[0.02499,1.1658,-0.09134,-1.0995], "fy":[-1.06781,0.05793,1.06759,-0.05816]}, + {"t":3.69482, "x":8.54432, "y":4.0, "heading":-0.67116, "vx":-1.29954, "vy":0.0, "omega":1.99193, "ax":0.0, "ay":-0.00001, "alpha":-0.37115, "fx":[0.13019,1.57904,-0.19748,-1.5118], "fy":[-1.48285,0.16389,1.48251,-0.16423]}, + {"t":3.72275, "x":8.50804, "y":4.0, "heading":-0.61553, "vx":-1.29954, "vy":0.0, "omega":1.98156, "ax":0.0, "ay":-0.00002, "alpha":-0.50093, "fx":[0.29763,2.09445,-0.36915,-2.02298], "fy":[-1.99773,0.33433,1.9973,-0.33476]}, + {"t":3.75067, "x":8.47175, "y":4.0, "heading":-0.5602, "vx":-1.29954, "vy":-0.00001, "omega":1.96758, "ax":0.0, "ay":-0.00002, "alpha":-0.66708, "fx":[0.55066,2.74256,-0.63132,-2.66195], "fy":[-2.64232,0.59462,2.64188,-0.59504]}, + {"t":3.7786, "x":8.43546, "y":4.0, "heading":-0.50526, "vx":-1.29954, "vy":-0.00001, "omega":1.94895, "ax":0.0, "ay":-0.00001, "alpha":-0.88308, "fx":[0.92505,3.56707,-1.02094,-3.47123], "fy":[-3.45927,0.98185,3.45896,-0.98211]}, + {"t":3.80652, "x":8.39917, "y":4.0, "heading":-0.45083, "vx":-1.29954, "vy":-0.00001, "omega":1.92429, "ax":0.0, "ay":0.0, "alpha":-1.16627, "fx":[1.47012,4.62129,-1.58922,-4.50224], "fy":[-4.50083,1.54823,4.50087,-1.54804]}, + {"t":3.83444, "x":8.36288, "y":4.0, "heading":-0.3971, "vx":-1.29954, "vy":-0.00001, "omega":1.89172, "ax":0.0, "ay":0.00004, "alpha":-1.53888, "fx":[2.25444,5.96942,-2.4067,-5.81722], "fy":[-5.82986,2.36523,5.83055,-2.36417]}, + {"t":3.86237, "x":8.32659, "y":4.0, "heading":-0.34427, "vx":-1.29954, "vy":-0.00001, "omega":1.84875, "ax":0.0, "ay":0.00009, "alpha":-2.02932, "fx":[3.37035,7.68849,-3.56743,-7.49146], "fy":[-7.52185,3.52877,7.52357,-3.52622]}, + {"t":3.89029, "x":8.2903, "y":4.0, "heading":-0.29265, "vx":-1.29954, "vy":0.0, "omega":1.79208, "ax":0.0, "ay":0.00016, "alpha":-2.67014, "fx":[4.93338,9.85715,-5.1886,-9.60199], "fy":[-9.65397,5.158,9.65709,-5.15316]}, + {"t":3.91822, "x":8.25402, "y":4.0, "heading":-0.24261, "vx":-1.29954, "vy":0.0, "omega":1.71752, "ax":0.0, "ay":0.00025, "alpha":-3.49878, "fx":[7.08474,12.55622,-7.41103,-12.22999], "fy":[-12.30509,7.39536,12.3098,-7.38742]}, + {"t":3.94614, "x":8.21773, "y":4.0, "heading":-0.19464, "vx":-1.29954, "vy":0.00001, "omega":1.61982, "ax":0.0, "ay":0.00035, "alpha":-4.55107, "fx":[9.97538,15.84538,-10.3831,-15.43772], "fy":[-15.53359,10.38896,15.53985,-10.37769]}, + {"t":3.97407, "x":8.18144, "y":4.0, "heading":-0.14941, "vx":-1.29954, "vy":0.00002, "omega":1.49273, "ax":0.0, "ay":0.00041, "alpha":-5.85714, "fx":[13.75139,19.7542,-14.24235,-19.26329], "fy":[-19.36784,14.26997,19.37636,-14.25808]}, + {"t":4.00199, "x":8.14515, "y":4.0, "heading":-0.10773, "vx":-1.29954, "vy":0.00003, "omega":1.32918, "ax":0.0, "ay":0.00034, "alpha":-7.4316, "fx":[18.52025,24.25712,-19.07709,-23.70034], "fy":[-23.78608,19.10912,23.80468,-19.11082]}, + {"t":4.02991, "x":8.10886, "y":4.0, "heading":-0.07061, "vx":-1.29954, "vy":0.00004, "omega":1.12166, "ax":0.0, "ay":0.00004, "alpha":-9.28294, "fx":[24.36483,29.31572,-24.93151,-28.7491], "fy":[-28.75721,24.90961,28.83008,-24.98033]}, + {"t":4.05784, "x":8.07257, "y":4.0, "heading":-0.03929, "vx":-1.29954, "vy":0.00004, "omega":0.86244, "ax":0.0, "ay":-0.00064, "alpha":-11.38159, "fx":[31.1968,34.86839,-31.71495,-34.35025], "fy":[-34.11811,31.45369,34.42711,-31.79467]}, + {"t":4.08576, "x":8.03628, "y":4.0, "heading":-0.01521, "vx":-1.29954, "vy":0.00002, "omega":0.54461, "ax":0.01296, "ay":-0.00125, "alpha":-13.89759, "fx":[40.79579,42.07246,-40.45429,-41.76606], "fy":[-39.74865,38.5266,40.16592,-39.00658]}, + {"t":4.11369, "x":8.0, "y":4.0, "heading":0.0, "vx":-1.29917, "vy":-0.00001, "omega":0.15653, "ax":-0.01281, "ay":-0.00016, "alpha":-3.26071, "fx":[9.35052,9.34958,-9.67141,-9.66924], "fy":[-9.42711,9.74746,9.07009,-9.39834]}, + {"t":4.14908, "x":7.95401, "y":4.0, "heading":0.00554, "vx":-1.29963, "vy":-0.00002, "omega":0.04112, "ax":0.0, "ay":0.00023, "alpha":-1.03894, "fx":[3.04835,3.01914,-3.04841,-3.01915], "fy":[-2.97817,3.12296,2.87189,-3.00511]}, + {"t":4.18448, "x":7.90801, "y":4.0, "heading":0.007, "vx":-1.29963, "vy":-0.00001, "omega":0.00435, "ax":0.0, "ay":0.00021, "alpha":-0.36015, "fx":[1.05647,1.04427,-1.05649,-1.04429], "fy":[-1.03069,1.08103,1.00292,-1.04257]}, + {"t":4.21987, "x":7.86201, "y":4.0, "heading":0.00715, "vx":-1.29963, "vy":0.0, "omega":-0.0084, "ax":0.00002, "ay":0.00011, "alpha":-0.13744, "fx":[0.40085,0.39648,-0.40026,-0.3959], "fy":[-0.39558,0.40823,0.39269,-0.39996]}, + {"t":4.25527, "x":7.816, "y":4.0, "heading":0.00685, "vx":-1.29963, "vy":0.0, "omega":-0.01327, "ax":0.75025, "ay":0.00013, "alpha":-0.05627, "fx":[9.53901,9.53761,9.21724,9.21864], "fy":[-0.16398,0.16519,0.17059,-0.16551]}, + {"t":4.29066, "x":7.77047, "y":4.0, "heading":0.00638, "vx":-1.27307, "vy":0.00001, "omega":-0.01526, "ax":2.98937, "ay":-0.00003, "alpha":-0.02276, "fx":[37.42959,37.42931,37.30457,37.30485], "fy":[-0.06993,0.06172,0.07697,-0.07037]}, + {"t":4.32606, "x":7.72729, "y":4.0, "heading":0.00584, "vx":-1.16726, "vy":0.00001, "omega":-0.01606, "ax":2.99471, "ay":-0.00002, "alpha":-0.00831, "fx":[37.45457,37.45467,37.4131,37.413], "fy":[-0.02766,0.02048,0.03397,-0.02769]}, + {"t":4.36145, "x":7.68785, "y":4.0, "heading":0.00527, "vx":-1.06126, "vy":0.0, "omega":-0.01636, "ax":2.99648, "ay":-0.00002, "alpha":-0.00133, "fx":[37.45728,37.45748,37.45467,37.45447], "fy":[-0.00658,0.0,0.01227,-0.00647]}, + {"t":4.39685, "x":7.65216, "y":4.0, "heading":0.0047, "vx":-0.9552, "vy":0.0, "omega":-0.01641, "ax":2.99736, "ay":-0.00001, "alpha":0.00223, "fx":[37.45888,37.45907,37.47516,37.47496], "fy":[0.00467,-0.00992,-0.00023,0.00481]}, + {"t":4.43225, "x":7.62023, "y":4.0, "heading":0.00411, "vx":-0.84911, "vy":0.0, "omega":-0.01633, "ax":2.99789, "ay":-0.00001, "alpha":0.00437, "fx":[37.46021,37.46037,37.48705,37.4869], "fy":[0.01178,-0.01541,-0.0089,0.0119]}, + {"t":4.46764, "x":7.59205, "y":4.0, "heading":0.00354, "vx":-0.743, "vy":0.0, "omega":-0.01617, "ax":2.99824, "ay":-0.00001, "alpha":0.0062, "fx":[37.46023,37.46035,37.49585,37.49573], "fy":[0.01803,-0.02005,-0.01671,0.01814]}, + {"t":4.50304, "x":7.56763, "y":4.0, "heading":0.00296, "vx":-0.63687, "vy":0.0, "omega":-0.01595, "ax":2.99849, "ay":-0.00001, "alpha":0.00863, "fx":[37.45726,37.45735,37.50511,37.50502], "fy":[0.026,-0.02649,-0.02618,0.0261]}, + {"t":4.53843, "x":7.54697, "y":4.0, "heading":0.0024, "vx":-0.53074, "vy":0.0, "omega":-0.01565, "ax":2.99868, "ay":-0.00001, "alpha":0.01289, "fx":[37.44823,37.44833,37.51886,37.51876], "fy":[0.03933,-0.03859,-0.04077,0.03945]}, + {"t":4.57383, "x":7.53006, "y":4.0, "heading":0.00185, "vx":-0.4246, "vy":0.0, "omega":-0.01519, "ax":2.99883, "ay":-0.00001, "alpha":0.02164, "fx":[37.42593,37.42607,37.54482,37.54468], "fy":[0.06596,-0.06458,-0.06807,0.06612]}, + {"t":4.60922, "x":7.51691, "y":4.0, "heading":0.00131, "vx":-0.31846, "vy":0.0, "omega":-0.01442, "ax":2.99895, "ay":-0.00001, "alpha":0.04193, "fx":[37.3709,37.37111,37.60278,37.60257], "fy":[0.12724,-0.12667,-0.12859,0.12744]}, + {"t":4.64462, "x":7.50751, "y":4.0, "heading":0.0008, "vx":-0.21231, "vy":0.0, "omega":-0.01294, "ax":2.99904, "ay":-0.00001, "alpha":0.09475, "fx":[37.22538,37.2257,37.7507,37.75037], "fy":[0.2871,-0.29093,-0.28403,0.28726]}, + {"t":4.68001, "x":7.50188, "y":4.0, "heading":0.00034, "vx":-0.10616, "vy":0.0, "omega":-0.00959, "ax":2.99912, "ay":-0.00001, "alpha":0.27085, "fx":[36.66477,36.66519,38.04907,38.57712], "fy":[0.76415,-0.74885,-0.74673,0.73084]}, + {"t":4.71541, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/deploy/choreo/LineRotateTest.traj b/deploy/choreo/LineRotateTest.traj new file mode 100644 index 00000000..dd486b47 --- /dev/null +++ b/deploy/choreo/LineRotateTest.traj @@ -0,0 +1,187 @@ +{ + "name":"LineRotateTest", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.5, "y":4.0, "heading":0.0, "intervals":70, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":10.0, "y":4.0, "heading":3.141592653589793, "intervals":70, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.5, "y":4.0, "heading":0.0, "intervals":28, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":1.3}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":3.0}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInLane", "props":{"tolerance":0.01}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepOutCircle", "props":{"x":4.491, "y":4.026, "r":1.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading", "val":0.0}, "intervals":70, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x + 2.5 m", "val":10.0}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading + 180 deg", "val":3.141592653589793}, "intervals":70, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"CentreStart.x", "val":7.5}, "y":{"exp":"CentreStart.y", "val":4.0}, "heading":{"exp":"CentreStart.heading", "val":0.0}, "intervals":28, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"MaxVelocity", "val":1.3}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAcceleration", "props":{"max":{"exp":"MaxAcceleration", "val":3.0}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"3 rad / s", "val":3.0}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInLane", "props":{"tolerance":{"exp":"0.01 m", "val":0.01}}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepOutCircle", "props":{"x":{"exp":"Reef.x", "val":4.491}, "y":{"exp":"Reef.y", "val":4.026}, "r":{"exp":"1 m", "val":1.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,2.35741,4.71481], + "samples":[ + {"t":0.0, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.99812, "ay":0.00001, "alpha":7.56251, "fx":[17.04565,16.60747,58.12716,58.12552], "fy":[24.53471,-24.54543,-21.92054,21.93188]}, + {"t":0.03368, "x":7.5017, "y":4.0, "heading":0.0, "vx":0.10097, "vy":0.0, "omega":0.25468, "ax":2.99897, "ay":0.00001, "alpha":6.28995, "fx":[20.48677,20.13162,54.66754,54.66268], "fy":[20.23376,-20.24687,-18.39444,18.40815]}, + {"t":0.06735, "x":7.5068, "y":4.0, "heading":0.00858, "vx":0.20197, "vy":0.0, "omega":0.46651, "ax":2.99887, "ay":0.00001, "alpha":5.23026, "fx":[23.20383,23.19873,51.87933,51.66159], "fy":[16.57869,-16.84331,-15.28565,15.55084]}, + {"t":0.10103, "x":7.5153, "y":4.0, "heading":0.02429, "vx":0.30296, "vy":0.0, "omega":0.64265, "ax":2.99874, "ay":0.00001, "alpha":4.35902, "fx":[25.38451,25.78371,49.63383,49.13516], "fy":[13.54369,-14.15018,-12.62664,13.23367]}, + {"t":0.13471, "x":7.52721, "y":4.0, "heading":0.04593, "vx":0.40395, "vy":0.0, "omega":0.78945, "ax":2.99859, "ay":0.00001, "alpha":3.65216, "fx":[27.13631,27.88775,47.85829,47.04703], "fy":[11.05729,-12.01254,-10.39629,11.35204]}, + {"t":0.16839, "x":7.54251, "y":4.0, "heading":0.07252, "vx":0.50493, "vy":0.0, "omega":0.91245, "ax":2.99839, "ay":0.00001, "alpha":3.06302, "fx":[28.55866,29.71782,46.36224,45.2806], "fy":[8.99858,-10.25792,-8.52709,9.78691]}, + {"t":0.20206, "x":7.56122, "y":4.0, "heading":0.10325, "vx":0.60591, "vy":0.0, "omega":1.0156, "ax":2.99812, "ay":0.00001, "alpha":2.57763, "fx":[29.76976,31.16565,45.13447,43.83605], "fy":[7.3002,-8.80397,-6.95747,8.46171]}, + {"t":0.23574, "x":7.58332, "y":4.0, "heading":0.13745, "vx":0.70688, "vy":0.0, "omega":1.10241, "ax":2.99774, "ay":0.00001, "alpha":2.17345, "fx":[30.81157,32.31447,44.10521,42.65594], "fy":[5.89273,-7.57118,-5.63857,7.31752]}, + {"t":0.26942, "x":7.60883, "y":4.0, "heading":0.17457, "vx":0.80783, "vy":0.0, "omega":1.17561, "ax":2.99718, "ay":0.00001, "alpha":1.79771, "fx":[31.77761,33.52931,43.05144,41.5008], "fy":[4.67996,-6.4493,-4.50957,6.27954]}, + {"t":0.3031, "x":7.63773, "y":4.0, "heading":0.21417, "vx":0.90877, "vy":0.0, "omega":1.23615, "ax":2.99625, "ay":0.00002, "alpha":1.52678, "fx":[32.34875,34.3713,42.34554,40.74701], "fy":[3.74193,-5.54958,-3.60988,5.4184]}, + {"t":0.33677, "x":7.67004, "y":4.0, "heading":0.2558, "vx":1.00968, "vy":0.0, "omega":1.28757, "ax":2.9944, "ay":0.00003, "alpha":1.2291, "fx":[33.23167,35.27371,41.39946,39.81528], "fy":[2.88372,-4.64855,-2.8041,4.57033]}, + {"t":0.37045, "x":7.70574, "y":4.0, "heading":0.29916, "vx":1.11052, "vy":0.0, "omega":1.32896, "ax":2.98896, "ay":0.00005, "alpha":1.06377, "fx":[33.46312,35.70961,40.91724,39.35788], "fy":[2.3029,-4.01728,-2.23366,3.95043]}, + {"t":0.40413, "x":7.74483, "y":4.0, "heading":0.34391, "vx":1.21118, "vy":0.00001, "omega":1.36478, "ax":2.62572, "ay":-0.00008, "alpha":0.86262, "fx":[29.52472,31.64283,35.79464,34.32357], "fy":[1.70785,-3.28232,-1.67234,3.24262]}, + {"t":0.4378, "x":7.78711, "y":4.0, "heading":0.38988, "vx":1.29961, "vy":0.0, "omega":1.39383, "ax":0.00035, "ay":-0.00049, "alpha":0.84299, "fx":[-2.987,-2.02602,3.31099,1.71946], "fy":[1.42799,-2.97596,-1.43623,2.9595]}, + {"t":0.47148, "x":7.83088, "y":4.0, "heading":0.43682, "vx":1.29962, "vy":-0.00001, "omega":1.42222, "ax":0.0, "ay":-0.00014, "alpha":0.62174, "fx":[-2.48848,-0.95208,2.39608,1.04456], "fy":[0.98224,-2.26846,-0.98472,2.26386]}, + {"t":0.50516, "x":7.87465, "y":4.0, "heading":0.48471, "vx":1.29962, "vy":-0.00002, "omega":1.44316, "ax":0.0, "ay":-0.00001, "alpha":0.54593, "fx":[-2.22965,-0.80893,2.14798,0.89049], "fy":[0.81721,-1.98531,-0.81689,1.98441]}, + {"t":0.53884, "x":7.91841, "y":4.0, "heading":0.53331, "vx":1.29962, "vy":-0.00002, "omega":1.46155, "ax":0.0, "ay":0.00004, "alpha":0.37532, "fx":[-1.57691,-0.51578,1.51588,0.57677], "fy":[0.51582,-1.36041,-0.51465,1.361]}, + {"t":0.57251, "x":7.96218, "y":4.0, "heading":0.58254, "vx":1.29962, "vy":-0.00002, "omega":1.47419, "ax":0.0, "ay":0.00005, "alpha":0.33279, "fx":[-1.43188,-0.47246,1.36543,0.53887], "fy":[0.47227,-1.18804,-0.47086,1.18895]}, + {"t":0.60619, "x":8.00595, "y":4.0, "heading":0.63218, "vx":1.29962, "vy":-0.00002, "omega":1.48539, "ax":0.0, "ay":0.00004, "alpha":0.19321, "fx":[-0.8721,-0.30834,0.8209,0.35951], "fy":[0.30296,-0.65913,-0.30168,0.66008]}, + {"t":0.63987, "x":8.04972, "y":4.0, "heading":0.68221, "vx":1.29962, "vy":-0.00001, "omega":1.4919, "ax":0.0, "ay":0.00004, "alpha":0.15053, "fx":[-0.71065,-0.29106,0.65804,0.34363], "fy":[0.29007,-0.49427,-0.28894,0.49507]}, + {"t":0.67354, "x":8.09348, "y":4.0, "heading":0.73245, "vx":1.29962, "vy":-0.00001, "omega":1.49697, "ax":0.0, "ay":0.00003, "alpha":0.03325, "fx":[-0.22326,-0.18908,0.1873,0.225], "fy":[0.18495,-0.04687,-0.18405,0.0476]}, + {"t":0.70722, "x":8.13725, "y":4.0, "heading":0.78286, "vx":1.29962, "vy":-0.00001, "omega":1.49809, "ax":0.0, "ay":0.00003, "alpha":-0.0211, "fx":[0.00387,-0.16477,-0.03322,0.19409], "fy":[0.16586,0.1558,-0.16507,-0.15519]}, + {"t":0.7409, "x":8.18102, "y":4.0, "heading":0.83331, "vx":1.29962, "vy":-0.00001, "omega":1.49738, "ax":0.0, "ay":0.00002, "alpha":-0.1048, "fx":[0.35616,-0.14744,-0.37526,0.1665], "fy":[0.14664,0.481,-0.14599,-0.48043]}, + {"t":0.77458, "x":8.22479, "y":4.0, "heading":0.88374, "vx":1.29962, "vy":-0.00001, "omega":1.49385, "ax":0.0, "ay":0.00002, "alpha":-0.16098, "fx":[0.59567,-0.16539,-0.60874,0.17843], "fy":[0.16763,0.69201,-0.16704,-0.6915]}, + {"t":0.80825, "x":8.26855, "y":4.0, "heading":0.93405, "vx":1.29962, "vy":-0.00001, "omega":1.48843, "ax":0.0, "ay":0.00002, "alpha":-0.21358, "fx":[0.80936,-0.20911,-0.81715,0.21687], "fy":[0.21075,0.89583,-0.21022,-0.89534]}, + {"t":0.84193, "x":8.31232, "y":4.0, "heading":0.98418, "vx":1.29962, "vy":-0.00001, "omega":1.48124, "ax":0.0, "ay":0.00002, "alpha":-0.27605, "fx":[1.07388,-0.26504,-1.07635,0.26747], "fy":[0.26766,1.12849,-0.26715,-1.12802]}, + {"t":0.87561, "x":8.35609, "y":4.0, "heading":1.03406, "vx":1.29962, "vy":-0.00001, "omega":1.47194, "ax":0.0, "ay":0.00002, "alpha":-0.30091, "fx":[1.15783,-0.34142,-1.15677,0.34032], "fy":[0.34396,1.21684,-0.34345,-1.21634]}, + {"t":0.90929, "x":8.39986, "y":4.0, "heading":1.08363, "vx":1.29962, "vy":-0.00001, "omega":1.46181, "ax":0.0, "ay":0.00002, "alpha":-0.36481, "fx":[1.42083,-0.43351,-1.41641,0.42906], "fy":[0.43594,1.44714,-0.43538,-1.44659]}, + {"t":0.94296, "x":8.44362, "y":4.0, "heading":1.13286, "vx":1.29962, "vy":-0.00001, "omega":1.44952, "ax":0.0, "ay":0.00003, "alpha":-0.36666, "fx":[1.39762,-0.51502,-1.38925,0.50662], "fy":[0.51685,1.43497,-0.51618,-1.43431]}, + {"t":0.97664, "x":8.48739, "y":4.0, "heading":1.18168, "vx":1.29962, "vy":-0.00001, "omega":1.43717, "ax":0.0, "ay":0.00003, "alpha":-0.4194, "fx":[1.60253,-0.62648,-1.59362,0.61753], "fy":[0.62795,1.61042,-0.62709,-1.60956]}, + {"t":1.01032, "x":8.53116, "y":3.99999, "heading":1.23008, "vx":1.29962, "vy":0.0, "omega":1.42305, "ax":0.0, "ay":0.00005, "alpha":-0.4003, "fx":[1.49051,-0.68321,-1.47707,0.66973], "fy":[0.6829,1.50816,-0.68173,-1.50699]}, + {"t":1.04399, "x":8.57493, "y":3.99999, "heading":1.278, "vx":1.29962, "vy":0.0, "omega":1.40957, "ax":0.0, "ay":0.00007, "alpha":-0.42558, "fx":[1.5755,-0.77214,-1.56442,0.76103], "fy":[0.77162,1.56941,-0.76997,-1.56775]}, + {"t":1.07767, "x":8.61869, "y":3.99999, "heading":1.32547, "vx":1.29962, "vy":0.0, "omega":1.39523, "ax":0.0, "ay":0.00009, "alpha":-0.37956, "fx":[1.3682,-0.76178,-1.35349,0.74704], "fy":[0.75795,1.36597,-0.75567,-1.36367]}, + {"t":1.11135, "x":8.66246, "y":3.99999, "heading":1.37246, "vx":1.29962, "vy":0.0, "omega":1.38245, "ax":0.0, "ay":0.00012, "alpha":-0.35836, "fx":[1.27941,-0.75614,-1.27056,0.74726], "fy":[0.75273,1.25883,-0.74971,-1.25579]}, + {"t":1.14503, "x":8.70623, "y":3.99999, "heading":1.41902, "vx":1.29962, "vy":0.00001, "omega":1.37038, "ax":0.0, "ay":0.00014, "alpha":-0.26759, "fx":[0.93841,-0.60519,-0.92922,0.59597], "fy":[0.59649,0.91466,-0.59296,-0.91109]}, + {"t":1.1787, "x":8.75, "y":4.0, "heading":1.46517, "vx":1.29962, "vy":0.00001, "omega":1.36137, "ax":0.0, "ay":0.00012, "alpha":-0.17402, "fx":[0.62373,-0.39294,-0.62575,0.39493], "fy":[0.38507,0.58457,-0.38209,-0.58153]}, + {"t":1.21238, "x":8.79376, "y":4.0, "heading":1.51101, "vx":1.29962, "vy":0.00002, "omega":1.35551, "ax":0.0, "ay":0.00005, "alpha":-0.02919, "fx":[0.15486,-0.03376,-0.16367,0.04254], "fy":[0.02144,0.10923,-0.02024,-0.10795]}, + {"t":1.24606, "x":8.83753, "y":4.0, "heading":1.55666, "vx":1.29962, "vy":0.00002, "omega":1.35453, "ax":0.0, "ay":-0.00004, "alpha":0.096, "fx":[-0.21398,0.32281,0.19252,-0.30138], "fy":[-0.33486,-0.26745,0.33386,0.26657]}, + {"t":1.27974, "x":8.8813, "y":4.0, "heading":1.60228, "vx":1.29962, "vy":0.00002, "omega":1.35776, "ax":0.0, "ay":-0.00011, "alpha":0.22274, "fx":[-0.56853,0.70264,0.54073,-0.67487], "fy":[-0.71764,-0.62084,0.7147,0.61809]}, + {"t":1.31341, "x":8.92507, "y":4.0, "heading":1.64801, "vx":1.29962, "vy":0.00001, "omega":1.36526, "ax":0.0, "ay":-0.00014, "alpha":0.29653, "fx":[-0.74566,0.9543,0.71214,-0.92081], "fy":[-0.96729,-0.79161,0.96367,0.78825]}, + {"t":1.34709, "x":8.96883, "y":4.0, "heading":1.69399, "vx":1.29962, "vy":0.00001, "omega":1.37525, "ax":0.0, "ay":-0.00012, "alpha":0.3462, "fx":[-0.83701,1.15953,0.77324,-1.09578], "fy":[-1.15739,-0.88789,1.15431,0.88514]}, + {"t":1.38077, "x":9.0126, "y":4.0, "heading":1.7403, "vx":1.29962, "vy":0.0, "omega":1.38691, "ax":0.0, "ay":-0.00008, "alpha":0.36663, "fx":[-0.85006,1.24347,0.80105,-1.19449], "fy":[-1.25346,-0.89169,1.25121,0.88977]}, + {"t":1.41444, "x":9.05637, "y":4.0, "heading":1.78701, "vx":1.29962, "vy":0.0, "omega":1.39925, "ax":0.0, "ay":-0.00005, "alpha":0.37452, "fx":[-0.83442,1.31195,0.78987,-1.26743], "fy":[-1.29877,-0.8466,1.2973,0.84537]}, + {"t":1.44812, "x":9.10014, "y":4.0, "heading":1.83413, "vx":1.29962, "vy":0.0, "omega":1.41187, "ax":0.0, "ay":-0.00003, "alpha":0.36628, "fx":[-0.76705,1.32062,0.72709,-1.28069], "fy":[-1.29691,-0.76659,1.29606,0.76583]}, + {"t":1.4818, "x":9.1439, "y":4.0, "heading":1.88168, "vx":1.29962, "vy":0.0, "omega":1.4242, "ax":0.0, "ay":-0.00002, "alpha":0.34731, "fx":[-0.67879,1.28415,0.64357,-1.24896], "fy":[-1.25418,-0.67004,1.25365,0.66966]}, + {"t":1.51548, "x":9.18767, "y":4.0, "heading":1.92964, "vx":1.29962, "vy":0.0, "omega":1.4359, "ax":0.0, "ay":-0.00001, "alpha":0.32295, "fx":[-0.59908,1.22015,0.5687,-1.18979], "fy":[-1.17824,-0.57815,1.17778,0.57811]}, + {"t":1.54915, "x":9.23144, "y":4.0, "heading":1.978, "vx":1.29962, "vy":0.0, "omega":1.44678, "ax":0.0, "ay":-0.00001, "alpha":0.2839, "fx":[-0.49267,1.09856,0.46148,-1.06739], "fy":[-1.04922,-0.46658,1.04879,0.4667]}, + {"t":1.58283, "x":9.27521, "y":4.0, "heading":2.02672, "vx":1.29962, "vy":0.0, "omega":1.45634, "ax":0.0, "ay":-0.00001, "alpha":0.24379, "fx":[-0.39767,0.96438,0.36917,-0.93591], "fy":[-0.90778,-0.36716,0.90725,0.36743]}, + {"t":1.61651, "x":9.31897, "y":4.0, "heading":2.07577, "vx":1.29962, "vy":0.0, "omega":1.46455, "ax":0.0, "ay":-0.00001, "alpha":0.19905, "fx":[-0.30232,0.81147,0.26951,-0.77869], "fy":[-0.74499,-0.26954,0.74447,0.26971]}, + {"t":1.65019, "x":9.36274, "y":4.0, "heading":2.12509, "vx":1.29962, "vy":0.0, "omega":1.47125, "ax":0.0, "ay":-0.00001, "alpha":0.15989, "fx":[-0.26084,0.68561,0.23233,-0.65712], "fy":[-0.5747,-0.18738,0.57414,0.18742]}, + {"t":1.68386, "x":9.40651, "y":4.0, "heading":2.17464, "vx":1.29962, "vy":0.0, "omega":1.47663, "ax":0.0, "ay":-0.00001, "alpha":0.11616, "fx":[-0.19125,0.52192,0.16054,-0.49123], "fy":[-0.40816,-0.12223,0.40761,0.12203]}, + {"t":1.71754, "x":9.45028, "y":4.0, "heading":2.22437, "vx":1.29962, "vy":0.0, "omega":1.48055, "ax":0.0, "ay":-0.00002, "alpha":0.07027, "fx":[-0.11637,0.36415,0.05088,-0.29869], "fy":[-0.23031,-0.06968,0.22962,0.06938]}, + {"t":1.75122, "x":9.49404, "y":4.0, "heading":2.27423, "vx":1.29962, "vy":-0.00001, "omega":1.48291, "ax":0.0, "ay":-0.00002, "alpha":0.02664, "fx":[-0.06261,0.14547,0.04266,-0.12554], "fy":[-0.07641,-0.04164,0.07582,0.04113]}, + {"t":1.78489, "x":9.53781, "y":4.0, "heading":2.32417, "vx":1.29962, "vy":-0.00001, "omega":1.48381, "ax":0.0, "ay":-0.00002, "alpha":-0.01641, "fx":[-0.04771,-0.01089,0.01133,0.04724], "fy":[0.10712,-0.022,-0.10757,0.02167]}, + {"t":1.81857, "x":9.58158, "y":4.0, "heading":2.37414, "vx":1.29962, "vy":-0.00001, "omega":1.48326, "ax":0.0, "ay":0.00001, "alpha":-0.04145, "fx":[0.02249,-0.14947,0.08784,0.03918], "fy":[0.24496,-0.02812,-0.24462,0.02844]}, + {"t":1.85225, "x":9.62535, "y":4.0, "heading":2.42409, "vx":1.29962, "vy":-0.00001, "omega":1.48186, "ax":0.0, "ay":0.00009, "alpha":-0.09166, "fx":[-0.06543,-0.31011,0.02598,0.34949], "fy":[0.41919,-0.04295,-0.41681,0.04531]}, + {"t":1.88593, "x":9.66911, "y":4.0, "heading":2.47399, "vx":1.29962, "vy":0.0, "omega":1.47877, "ax":-0.00036, "ay":0.00029, "alpha":-0.05865, "fx":[-0.34324,0.30886,-0.18949,0.20609], "fy":[0.52126,-0.07509,-0.51396,0.0824]}, + {"t":1.9196, "x":9.71288, "y":4.0, "heading":2.5238, "vx":1.29961, "vy":0.00001, "omega":1.4768, "ax":-2.62518, "ay":0.00009, "alpha":-0.20825, "fx":[-32.6789,-34.11157,-32.46208,-32.00637], "fy":[0.64288,-0.11875,-0.64105,0.12167]}, + {"t":1.95328, "x":9.75516, "y":4.0, "heading":2.57353, "vx":1.2112, "vy":0.00001, "omega":1.46979, "ax":-2.98893, "ay":-0.00001, "alpha":-0.20145, "fx":[-37.411,-38.34526,-37.0927,-36.59765], "fy":[0.74393,-0.17921,-0.74491,0.17955]}, + {"t":1.98696, "x":9.79426, "y":4.0, "heading":2.62303, "vx":1.11054, "vy":0.00001, "omega":1.463, "ax":-2.99439, "ay":-0.00001, "alpha":-0.2255, "fx":[-37.66516,-38.27347,-37.18529,-36.59551], "fy":[0.93925,-0.26997,-0.94065,0.27082]}, + {"t":2.02063, "x":9.82996, "y":4.0, "heading":2.6723, "vx":1.0097, "vy":0.00001, "omega":1.45541, "ax":-2.99624, "ay":-0.00001, "alpha":-0.2643, "fx":[-37.71335,-38.49632,-37.10741,-36.49504], "fy":[1.06146,-0.36572,-1.06337,0.36723]}, + {"t":2.05431, "x":9.86226, "y":4.0, "heading":2.72131, "vx":0.90879, "vy":0.00001, "omega":1.44651, "ax":-2.99718, "ay":-0.00001, "alpha":-0.3177, "fx":[-37.88028,-38.67243,-36.98781,-36.31827], "fy":[1.25109,-0.49703,-1.25458,0.5002]}, + {"t":2.08799, "x":9.89117, "y":4.0, "heading":2.77003, "vx":0.80785, "vy":0.00001, "omega":1.43581, "ax":-2.99774, "ay":-0.00001, "alpha":-0.35945, "fx":[-38.01716,-38.79885,-36.87053,-36.20035], "fy":[1.38806,-0.63551,-1.39294,0.64013]}, + {"t":2.12167, "x":9.91667, "y":4.0, "heading":2.81838, "vx":0.7069, "vy":0.00001, "omega":1.4237, "ax":-2.99811, "ay":0.0, "alpha":-0.41611, "fx":[-38.1826,-38.9734,-36.716,-36.03367], "fy":[1.57096,-0.80949,-1.57845,0.81675]}, + {"t":2.15534, "x":9.93878, "y":4.0, "heading":2.86633, "vx":0.60593, "vy":0.00001, "omega":1.40969, "ax":-2.99838, "ay":0.0, "alpha":-0.47991, "fx":[-38.42046,-39.17658,-36.48943,-35.83263], "fy":[1.73128,-1.00104,-1.74316,1.01269]}, + {"t":2.18902, "x":9.95749, "y":4.0, "heading":2.9138, "vx":0.50495, "vy":0.00001, "omega":1.39353, "ax":-2.99858, "ay":0.0, "alpha":-0.52872, "fx":[-38.47988,-39.2952,-36.38653,-35.76757], "fy":[1.91939,-1.22862,-1.93334,1.24233]}, + {"t":2.2227, "x":9.97279, "y":4.0, "heading":2.96073, "vx":0.40397, "vy":0.00001, "omega":1.37572, "ax":-2.99874, "ay":0.0, "alpha":-0.60894, "fx":[-38.80028,-39.50962,-36.09104,-35.53609], "fy":[2.10592,-1.48624,-2.12779,1.50788]}, + {"t":2.25638, "x":9.9847, "y":4.0, "heading":3.00706, "vx":0.30298, "vy":0.00001, "omega":1.35521, "ax":-2.99887, "ay":-0.00001, "alpha":-0.68054, "fx":[-39.04648,-39.67432,-35.84464,-35.37787], "fy":[2.28422,-1.76441,-2.31213,1.79207]}, + {"t":2.29005, "x":9.9932, "y":4.0, "heading":3.0527, "vx":0.20199, "vy":0.00001, "omega":1.33229, "ax":-2.99897, "ay":-0.00001, "alpha":-0.74522, "fx":[-39.32472,-39.74133,-35.61432,-35.26808], "fy":[2.438,-2.05223,-2.47057,2.08451]}, + {"t":2.32373, "x":9.9983, "y":4.0, "heading":3.09757, "vx":0.10099, "vy":0.00001, "omega":1.3072, "ax":-2.99905, "ay":-0.00001, "alpha":-0.83312, "fx":[-39.67839,-39.82309,-35.32434,-35.12692], "fy":[2.65988,-2.44001,-2.69583,2.47565]}, + {"t":2.35741, "x":10.0, "y":4.0, "heading":3.14159, "vx":-0.00001, "vy":0.00001, "omega":1.27914, "ax":-2.99811, "ay":-0.00001, "alpha":0.81285, "fx":[-35.16796,-35.36142,-39.68806,-39.68806], "fy":[-2.52261,2.52141,2.48856,-2.48768]}, + {"t":2.39108, "x":9.9983, "y":4.0, "heading":-3.09851, "vx":-0.10098, "vy":0.00001, "omega":1.30652, "ax":-2.99897, "ay":-0.00001, "alpha":0.75098, "fx":[-35.21431,-35.55893,-39.66911,-39.50611], "fy":[-2.1789,2.36165,2.14192,-2.32502]}, + {"t":2.42476, "x":9.9932, "y":4.0, "heading":-3.05452, "vx":-0.20198, "vy":0.00001, "omega":1.33181, "ax":-2.99887, "ay":-0.00001, "alpha":0.64934, "fx":[-35.48421,-35.98244,-39.38557,-39.0911], "fy":[-1.84508,2.17501,1.82093,-2.15124]}, + {"t":2.45844, "x":9.9847, "y":4.0, "heading":-3.00966, "vx":-0.30297, "vy":0.00001, "omega":1.35367, "ax":-2.99874, "ay":-0.00001, "alpha":0.57132, "fx":[-35.65391,-36.25252,-39.21279,-38.8178], "fy":[-1.53825,1.98096,1.52054,-1.96365]}, + {"t":2.49212, "x":9.97279, "y":4.0, "heading":-2.96408, "vx":-0.40396, "vy":0.00001, "omega":1.37291, "ax":-2.99858, "ay":-0.00001, "alpha":0.48993, "fx":[-35.90714,-36.54268,-38.97631,-38.50306], "fy":[-1.27427,1.80384,1.26329,-1.79328]}, + {"t":2.52579, "x":9.95749, "y":4.0, "heading":-2.91784, "vx":-0.50494, "vy":0.00001, "omega":1.38941, "ax":-2.99838, "ay":-0.00001, "alpha":0.44125, "fx":[-35.99512,-36.62239,-38.91054,-38.39105], "fy":[-1.03558,1.61993,1.02611,-1.61087]}, + {"t":2.55947, "x":9.93878, "y":4.0, "heading":-2.87105, "vx":-0.60592, "vy":0.00001, "omega":1.40427, "ax":-2.99811, "ay":-0.00001, "alpha":0.38165, "fx":[-36.1539,-36.81606,-38.7427,-38.19302], "fy":[-0.83067,1.44933,0.82426,-1.44333]}, + {"t":2.59315, "x":9.91668, "y":4.0, "heading":-2.82376, "vx":-0.70689, "vy":0.00001, "omega":1.41713, "ax":-2.99774, "ay":-0.00001, "alpha":0.32685, "fx":[-36.31183,-36.96613,-38.58193,-38.027], "fy":[-0.65012,1.27662,0.6458,-1.2727]}, + {"t":2.62682, "x":9.89117, "y":4.0, "heading":-2.77603, "vx":-0.80784, "vy":0.00001, "omega":1.42813, "ax":-2.99718, "ay":-0.00001, "alpha":0.27674, "fx":[-36.45543,-37.10343,-38.42144,-37.8785], "fy":[-0.49622,1.11141,0.49337,-1.10893]}, + {"t":2.6605, "x":9.86226, "y":4.0, "heading":-2.72794, "vx":-0.90878, "vy":0.00001, "omega":1.43745, "ax":-2.99624, "ay":-0.00001, "alpha":0.231, "fx":[-36.5901,-37.21106,-38.26246,-37.7485], "fy":[-0.36643,0.95194,0.36456,-0.95038]}, + {"t":2.69418, "x":9.82996, "y":4.0, "heading":-2.67953, "vx":-1.00968, "vy":0.00001, "omega":1.44523, "ax":-2.99439, "ay":-0.00001, "alpha":0.18943, "fx":[-36.73851,-37.21063,-38.11814,-37.65215], "fy":[-0.25725,0.79031,0.25574,-0.78907]}, + {"t":2.72786, "x":9.79426, "y":4.0, "heading":-2.63086, "vx":-1.11053, "vy":0.0, "omega":1.45161, "ax":-2.98893, "ay":-0.00001, "alpha":0.14754, "fx":[-36.69878,-37.49808,-37.83448,-37.41534], "fy":[-0.17319,0.65313,0.17242,-0.65293]}, + {"t":2.76153, "x":9.75517, "y":4.0, "heading":-2.58197, "vx":-1.21118, "vy":0.0, "omega":1.45658, "ax":-2.62555, "ay":-0.00015, "alpha":0.09896, "fx":[-32.02621,-33.78903,-32.90643,-32.55587], "fy":[-0.10812,0.50797,0.10524,-0.5126]}, + {"t":2.79521, "x":9.71289, "y":4.0, "heading":-2.53292, "vx":-1.29961, "vy":0.0, "omega":1.45991, "ax":-0.00036, "ay":-0.00028, "alpha":0.10752, "fx":[0.0778,0.89299,-0.65199,-0.33656], "fy":[-0.06383,0.40735,0.05689,-0.4143]}, + {"t":2.82889, "x":9.66912, "y":4.0, "heading":-2.48375, "vx":-1.29962, "vy":-0.00001, "omega":1.46353, "ax":0.0, "ay":-0.00006, "alpha":0.04648, "fx":[0.15702,-0.0047,-0.08875,-0.06364], "fy":[-0.0248,0.25401,0.0232,-0.25565]}, + {"t":2.86256, "x":9.62535, "y":4.0, "heading":-2.43446, "vx":-1.29962, "vy":-0.00001, "omega":1.4651, "ax":0.0, "ay":0.0, "alpha":0.00964, "fx":[-0.11511,0.10953,-0.03501,0.04062], "fy":[-0.00192,0.11658,0.00203,-0.1165]}, + {"t":2.89624, "x":9.58159, "y":4.0, "heading":-2.38512, "vx":-1.29962, "vy":-0.00001, "omega":1.46543, "ax":0.0, "ay":0.00003, "alpha":-0.03619, "fx":[-0.30256,0.09423,0.15888,0.04941], "fy":[0.00206,-0.0667,-0.00141,0.06733]}, + {"t":2.92992, "x":9.53782, "y":4.0, "heading":-2.33577, "vx":-1.29962, "vy":-0.00001, "omega":1.46421, "ax":0.0, "ay":0.00003, "alpha":-0.06227, "fx":[-0.3069,0.10879,0.24241,-0.04432], "fy":[-0.0091,-0.23434,0.00978,0.23503]}, + {"t":2.9636, "x":9.49405, "y":4.0, "heading":-2.28646, "vx":-1.29962, "vy":-0.00001, "omega":1.46211, "ax":0.0, "ay":0.00002, "alpha":-0.11273, "fx":[-0.50473,0.11466,0.47919,-0.08915], "fy":[-0.04213,-0.42499,0.04263,0.42561]}, + {"t":2.99727, "x":9.45028, "y":4.0, "heading":-2.23722, "vx":-1.29962, "vy":-0.00001, "omega":1.45831, "ax":0.0, "ay":0.00002, "alpha":-0.15664, "fx":[-0.68937,0.20511,0.64122,-0.15699], "fy":[-0.08863,-0.59675,0.08889,0.59731]}, + {"t":3.03095, "x":9.40652, "y":4.0, "heading":-2.18811, "vx":-1.29962, "vy":-0.00001, "omega":1.45304, "ax":0.0, "ay":0.00001, "alpha":-0.20352, "fx":[-0.86695,0.26425,0.82698,-0.2243], "fy":[-0.15466,-0.77911,0.15473,0.7796]}, + {"t":3.06463, "x":9.36275, "y":4.0, "heading":-2.13918, "vx":-1.29962, "vy":-0.00001, "omega":1.44618, "ax":0.0, "ay":0.00001, "alpha":-0.24697, "fx":[-1.05627,0.31781,0.97312,-0.23468], "fy":[-0.23272,-0.94825,0.23259,0.94876]}, + {"t":3.0983, "x":9.31898, "y":4.0, "heading":-2.09047, "vx":-1.29962, "vy":-0.00001, "omega":1.43787, "ax":0.0, "ay":0.00001, "alpha":-0.28454, "fx":[-1.13906,0.38088,1.10462,-0.34647], "fy":[-0.32344,-1.11093,0.32329,1.11139]}, + {"t":3.13198, "x":9.27521, "y":4.0, "heading":-2.04205, "vx":-1.29962, "vy":-0.00001, "omega":1.42828, "ax":0.0, "ay":0.00001, "alpha":-0.32273, "fx":[-1.26746,0.46973,1.23421,-0.43651], "fy":[-0.41916,-1.25024,0.41912,1.25064]}, + {"t":3.16566, "x":9.23145, "y":4.0, "heading":-1.99395, "vx":-1.29962, "vy":-0.00001, "omega":1.41742, "ax":0.0, "ay":0.00001, "alpha":-0.35034, "fx":[-1.34813,0.55413,1.31362,-0.51965], "fy":[-0.51091,-1.34635,0.51109,1.34673]}, + {"t":3.19934, "x":9.18768, "y":4.0, "heading":-1.94621, "vx":-1.29962, "vy":-0.00001, "omega":1.40562, "ax":0.0, "ay":0.00002, "alpha":-0.36972, "fx":[-1.3879,0.63722,1.35464,-0.60399], "fy":[-0.60547,-1.40364,0.6059,1.40418]}, + {"t":3.23301, "x":9.14391, "y":4.0, "heading":-1.89888, "vx":-1.29962, "vy":-0.00001, "omega":1.39317, "ax":0.0, "ay":0.00003, "alpha":-0.3789, "fx":[-1.38418,0.71715,1.34798,-0.68098], "fy":[-0.69106,-1.41464,0.69176,1.4156]}, + {"t":3.26669, "x":9.10014, "y":4.0, "heading":-1.85196, "vx":-1.29962, "vy":-0.00001, "omega":1.38041, "ax":0.0, "ay":0.00005, "alpha":-0.37752, "fx":[-1.34438,0.7673,1.30725,-0.7302], "fy":[-0.75018,-1.38438,0.75134,1.38593]}, + {"t":3.30037, "x":9.05638, "y":4.0, "heading":-1.80547, "vx":-1.29962, "vy":0.0, "omega":1.36769, "ax":0.0, "ay":0.00008, "alpha":-0.35314, "fx":[-1.21935,0.7542,1.17645,-0.71133], "fy":[-0.75937,-1.28481,0.76126,1.28708]}, + {"t":3.33404, "x":9.01261, "y":4.0, "heading":-1.75941, "vx":-1.29962, "vy":0.0, "omega":1.3558, "ax":0.0, "ay":0.00012, "alpha":-0.3085, "fx":[-1.03834,0.69238,0.99424,-0.64831], "fy":[-0.70624,-1.10662,0.70899,1.1097]}, + {"t":3.36772, "x":8.96884, "y":4.0, "heading":-1.71375, "vx":-1.29962, "vy":0.0, "omega":1.34541, "ax":0.0, "ay":0.00014, "alpha":-0.23737, "fx":[-0.7904,0.55582,0.75591,-0.52136], "fy":[-0.56231,-0.83281,0.56576,0.83652]}, + {"t":3.4014, "x":8.92507, "y":4.0, "heading":-1.66844, "vx":-1.29962, "vy":0.00001, "omega":1.33742, "ax":0.0, "ay":0.00013, "alpha":-0.12309, "fx":[-0.41432,0.28257,0.38224,-0.25052], "fy":[-0.29212,-0.44709,0.29522,0.45037]}, + {"t":3.43508, "x":8.88131, "y":4.0, "heading":-1.6234, "vx":-1.29962, "vy":0.00001, "omega":1.33327, "ax":0.0, "ay":0.00006, "alpha":0.01144, "fx":[-0.00312,-0.07627,-0.02401,0.10338], "fy":[0.06609,-0.02302,-0.06461,0.02463]}, + {"t":3.46875, "x":8.83754, "y":4.0, "heading":-1.5785, "vx":-1.29962, "vy":0.00001, "omega":1.33366, "ax":0.0, "ay":-0.00002, "alpha":0.14733, "fx":[0.38018,-0.47367,-0.39999,0.49345], "fy":[0.46377,0.37334,-0.46439,-0.37388]}, + {"t":3.50243, "x":8.79377, "y":4.0, "heading":-1.53359, "vx":-1.29962, "vy":0.00001, "omega":1.33862, "ax":0.0, "ay":-0.0001, "alpha":0.26582, "fx":[0.68208,-0.85232,-0.69373,0.86395], "fy":[0.84152,0.68477,-0.84408,-0.68727]}, + {"t":3.53611, "x":8.75, "y":4.0, "heading":-1.48851, "vx":-1.29962, "vy":0.00001, "omega":1.34757, "ax":0.0, "ay":-0.00013, "alpha":0.34507, "fx":[0.85102,-1.13095,-0.8558,1.1357], "fy":[1.1223,0.86127,-1.12565,-0.86458]}, + {"t":3.56978, "x":8.70624, "y":4.0, "heading":-1.44312, "vx":-1.29962, "vy":0.00001, "omega":1.35919, "ax":0.0, "ay":-0.00012, "alpha":0.39667, "fx":[0.929,-1.336,-0.92918,1.33614], "fy":[1.32867,0.9427,-1.33161,-0.94561]}, + {"t":3.60346, "x":8.66247, "y":4.0, "heading":-1.39735, "vx":-1.29962, "vy":0.0, "omega":1.37255, "ax":0.0, "ay":-0.00009, "alpha":0.42069, "fx":[0.93038,-1.45298,-0.92558,1.44814], "fy":[1.44952,0.94676,-1.45172,-0.94894]}, + {"t":3.63714, "x":8.6187, "y":4.0, "heading":-1.35113, "vx":-1.29962, "vy":0.0, "omega":1.38672, "ax":0.0, "ay":-0.00006, "alpha":0.42996, "fx":[0.89056,-1.52142,-0.88406,1.51489], "fy":[1.5211,0.9066,-1.52261,-0.9081]}, + {"t":3.67082, "x":8.57493, "y":4.0, "heading":-1.30443, "vx":-1.29962, "vy":0.0, "omega":1.4012, "ax":0.0, "ay":-0.00004, "alpha":0.41989, "fx":[0.81406,-1.51747,-0.80278,1.50616], "fy":[1.52064,0.8285,-1.52163,-0.82948]}, + {"t":3.70449, "x":8.53117, "y":4.0, "heading":-1.25724, "vx":-1.29962, "vy":0.0, "omega":1.41534, "ax":0.0, "ay":-0.00003, "alpha":0.40203, "fx":[0.72466,-1.48112,-0.71148,1.46791], "fy":[1.48713,0.7356,-1.48776,-0.73624]}, + {"t":3.73817, "x":8.4874, "y":4.0, "heading":-1.20957, "vx":-1.29962, "vy":-0.00001, "omega":1.42888, "ax":0.0, "ay":-0.00002, "alpha":0.37141, "fx":[0.62603,-1.3899,-0.60794,1.37177], "fy":[1.39907,0.63201,-1.39949,-0.63243]}, + {"t":3.77185, "x":8.44363, "y":4.0, "heading":-1.16145, "vx":-1.29962, "vy":-0.00001, "omega":1.44138, "ax":0.0, "ay":-0.00001, "alpha":0.33466, "fx":[0.53006,-1.26869,-0.50781,1.24641], "fy":[1.28083,0.52962,-1.28112,-0.52993]}, + {"t":3.80552, "x":8.39987, "y":4.0, "heading":-1.11291, "vx":-1.29962, "vy":-0.00001, "omega":1.45265, "ax":0.0, "ay":-0.00001, "alpha":0.29173, "fx":[0.44274,-1.11692,-0.4151,1.08925], "fy":[1.13183,0.4344,-1.13207,-0.43467]}, + {"t":3.8392, "x":8.3561, "y":4.0, "heading":-1.06399, "vx":-1.29962, "vy":-0.00001, "omega":1.46248, "ax":0.0, "ay":-0.00001, "alpha":0.23995, "fx":[0.36916,-0.92336,-0.33332,0.88748], "fy":[0.9418,0.35045,-0.94204,-0.35073]}, + {"t":3.87288, "x":8.31233, "y":4.0, "heading":-1.01474, "vx":-1.29962, "vy":-0.00001, "omega":1.47056, "ax":0.0, "ay":-0.00001, "alpha":0.18829, "fx":[0.31242,-0.72653,-0.27015,0.68422], "fy":[0.74718,0.28279,-0.74745,-0.28312]}, + {"t":3.90656, "x":8.26856, "y":4.0, "heading":-0.96521, "vx":-1.29962, "vy":-0.00001, "omega":1.4769, "ax":0.0, "ay":-0.00002, "alpha":0.12272, "fx":[0.28252,-0.46821,-0.22747,0.41313], "fy":[0.49332,0.23679,-0.49367,-0.23722]}, + {"t":3.94023, "x":8.2248, "y":4.0, "heading":-0.91548, "vx":-1.29962, "vy":-0.00001, "omega":1.48103, "ax":0.0, "ay":-0.00002, "alpha":0.06073, "fx":[0.27232,-0.22432,-0.2087,0.16066], "fy":[0.25078,0.21108,-0.25123,-0.21165]}, + {"t":3.97391, "x":8.18103, "y":4.0, "heading":-0.8656, "vx":-1.29962, "vy":-0.00001, "omega":1.48308, "ax":0.0, "ay":-0.00003, "alpha":-0.01932, "fx":[0.30646,0.09542,-0.22735,-0.17457], "fy":[-0.06362,0.2216,0.06303,-0.22238]}, + {"t":4.00759, "x":8.13726, "y":4.0, "heading":-0.81565, "vx":-1.29962, "vy":-0.00001, "omega":1.48243, "ax":0.0, "ay":-0.00004, "alpha":-0.09638, "fx":[0.35089,0.39775,-0.26174,-0.48693], "fy":[-0.36607,0.24645,0.36529,-0.24748]}, + {"t":4.04126, "x":8.09349, "y":4.0, "heading":-0.76573, "vx":-1.29962, "vy":-0.00001, "omega":1.47918, "ax":0.0, "ay":-0.00005, "alpha":-0.17752, "fx":[0.38945,0.71742,-0.29605,-0.81085], "fy":[-0.68128,0.2736,0.68027,-0.27489]}, + {"t":4.07494, "x":8.04973, "y":4.0, "heading":-0.71591, "vx":-1.29962, "vy":-0.00001, "omega":1.4732, "ax":0.0, "ay":-0.00005, "alpha":-0.26033, "fx":[0.43391,1.04011,-0.33958,-1.13449], "fy":[-1.00601,0.31321,1.00481,-0.31472]}, + {"t":4.10862, "x":8.00596, "y":4.0, "heading":-0.6663, "vx":-1.29962, "vy":-0.00001, "omega":1.46444, "ax":0.0, "ay":-0.00005, "alpha":-0.35023, "fx":[0.50053,1.39475,-0.41173,-1.48358], "fy":[-1.35572,0.38094,1.35455,-0.38248]}, + {"t":4.1423, "x":7.96219, "y":4.0, "heading":-0.61698, "vx":-1.29962, "vy":-0.00002, "omega":1.45264, "ax":0.0, "ay":-0.00003, "alpha":-0.45401, "fx":[0.62702,1.79585,-0.54158,-1.88132], "fy":[-1.75563,0.50466,1.75517,-0.50562]}, + {"t":4.17597, "x":7.91842, "y":4.0, "heading":-0.56806, "vx":-1.29962, "vy":-0.00002, "omega":1.43735, "ax":0.0, "ay":0.00006, "alpha":-0.56614, "fx":[0.79908,2.22726,-0.72677,-2.29967], "fy":[-2.17503,0.67936,2.17702,-0.67822]}, + {"t":4.20965, "x":7.87466, "y":4.0, "heading":-0.51966, "vx":-1.29962, "vy":-0.00002, "omega":1.41829, "ax":0.0, "ay":0.0003, "alpha":-0.70528, "fx":[1.06018,2.7532,-1.00417,-2.80912], "fy":[-2.67665,0.94125,2.68521,-0.93456]}, + {"t":4.24333, "x":7.83089, "y":3.99999, "heading":-0.47189, "vx":-1.29962, "vy":0.0, "omega":1.39453, "ax":0.00035, "ay":0.00087, "alpha":-0.80211, "fx":[1.58224,2.64803,-1.10754,-3.10538], "fy":[-3.18992,1.2572,3.21473,-1.23871]}, + {"t":4.277, "x":7.78712, "y":3.99999, "heading":-0.42493, "vx":-1.29961, "vy":0.00002, "omega":1.36752, "ax":2.6249, "ay":0.00001, "alpha":-0.96156, "fx":[34.26441,36.50414,31.22475,29.25178], "fy":[-3.62138,1.55062,3.66192,-1.5909]}, + {"t":4.31068, "x":7.74484, "y":4.0, "heading":-0.37887, "vx":-1.21121, "vy":0.00002, "omega":1.33514, "ax":2.98896, "ay":-0.00014, "alpha":-1.12437, "fx":[39.18184,41.56143,35.38818,33.31634], "fy":[-4.20709,1.98511,4.26762,-2.05252]}, + {"t":4.34436, "x":7.70575, "y":4.0, "heading":-0.33391, "vx":-1.11055, "vy":0.00002, "omega":1.29727, "ax":2.9944, "ay":-0.00009, "alpha":-1.30167, "fx":[39.62019,42.05667,35.11061,32.93263], "fy":[-4.91515,2.55622,4.99647,-2.6418]}, + {"t":4.37804, "x":7.67005, "y":4.0, "heading":-0.29022, "vx":-1.00971, "vy":0.00002, "omega":1.25344, "ax":2.99625, "ay":-0.00006, "alpha":-1.55301, "fx":[40.44581,42.80257,34.40575,32.15846], "fy":[-5.68653,3.23677,5.8109,-3.36426]}, + {"t":4.41171, "x":7.63774, "y":4.0, "heading":-0.24801, "vx":-0.9088, "vy":0.00001, "omega":1.20114, "ax":2.99718, "ay":-0.00005, "alpha":-1.80898, "fx":[41.10051,43.44637,33.7957,31.51658], "fy":[-6.57774,4.08368,6.73756,-4.2461]}, + {"t":4.44539, "x":7.60883, "y":4.0, "heading":-0.20756, "vx":-0.80786, "vy":0.00001, "omega":1.14021, "ax":2.99774, "ay":-0.00005, "alpha":-2.14539, "fx":[42.17505,44.35545,32.81376,30.54293], "fy":[-7.55405,5.08198,7.78515,-5.31544]}, + {"t":4.47907, "x":7.58333, "y":4.0, "heading":-0.16916, "vx":-0.70691, "vy":0.00001, "omega":1.06796, "ax":2.99812, "ay":-0.00005, "alpha":-2.51909, "fx":[43.21654,45.35259,31.76157,29.57523], "fy":[-8.66871,6.28376,8.98107,-6.59839]}, + {"t":4.51274, "x":7.56122, "y":4.0, "heading":-0.13319, "vx":-0.60594, "vy":0.00001, "omega":0.98313, "ax":2.99839, "ay":-0.00005, "alpha":-2.96491, "fx":[44.50788,46.55017,30.45165,28.40962], "fy":[-9.91831,7.69888,10.34727,-8.13012]}, + {"t":4.54642, "x":7.54252, "y":4.0, "heading":-0.10008, "vx":-0.50496, "vy":0.00001, "omega":0.88328, "ax":2.99859, "ay":-0.00005, "alpha":-3.52087, "fx":[46.1636,47.99021,28.80629,26.96929], "fy":[-11.43552,9.45332,12.04024,-10.06036]}, + {"t":4.5801, "x":7.52721, "y":4.0, "heading":-0.07034, "vx":-0.40398, "vy":0.00001, "omega":0.76471, "ax":2.99874, "ay":-0.00005, "alpha":-4.20221, "fx":[48.16229,49.75157,26.78955,25.23381], "fy":[-13.26731,11.59866,14.11588,-12.44962]}, + {"t":4.61378, "x":7.51531, "y":4.0, "heading":-0.04459, "vx":-0.30299, "vy":0.00001, "omega":0.62319, "ax":2.99887, "ay":-0.00005, "alpha":-5.05214, "fx":[50.65454,51.9327,24.27754,23.0787], "fy":[-15.51455,14.23698,16.72462,-15.44953]}, + {"t":4.64745, "x":7.5068, "y":4.0, "heading":-0.0236, "vx":-0.202, "vy":0.0, "omega":0.45305, "ax":2.99897, "ay":-0.00005, "alpha":-6.09815, "fx":[53.69991,54.61667,21.20418,20.42786], "fy":[-18.245,17.41963,19.98868,-19.16587]}, + {"t":4.68113, "x":7.5017, "y":4.0, "heading":-0.00834, "vx":-0.101, "vy":0.0, "omega":0.24768, "ax":2.99906, "ay":-0.00005, "alpha":-7.35447, "fx":[57.71141,57.96737,17.31994,16.95418], "fy":[-20.99336,20.91842,23.72933,-23.65713]}, + {"t":4.71481, "x":7.5, "y":4.0, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/robot.py b/robot.py index 427e6066..ab6f3c47 100644 --- a/robot.py +++ b/robot.py @@ -8,7 +8,7 @@ from phoenix6.configs import Slot0Configs from wpimath.geometry import Rotation2d, Translation3d -from autonomous.auto_base import AutoBase +from autonomous.auto_base import AutoBase, AutoBaseNoBalls from components.ballistics import BallisticsComponent from components.chassis import ChassisComponent, SwerveConfig from components.climber import ClimberComponent @@ -359,7 +359,7 @@ def disabledPeriodic(self) -> None: or self.port_vision.sees_multi_tag_target() ): selected_auto = self._automodes.chooser.getSelected() - if isinstance(selected_auto, AutoBase): + if isinstance(selected_auto, (AutoBase | AutoBaseNoBalls)): intended_start_pose = selected_auto.get_starting_pose() current_pose = self.chassis.get_pose() if intended_start_pose is not None: @@ -388,7 +388,7 @@ def disabledPeriodic(self) -> None: def _display_auto_trajectory(self) -> None: selected_auto = self._automodes.chooser.getSelected() - if isinstance(selected_auto, AutoBase): + if isinstance(selected_auto, (AutoBase | AutoBaseNoBalls)): selected_auto.display_trajectory() def robotPeriodic(self) -> None: