def setup(self):
     # empty waypoints are used for trajectories with only two points
     self.start_poses = [
         to_pose(-3.459, -1.7, math.pi),
         to_pose(-8.163, -1.7, math.pi),
         to_pose(-4.168, -1.7, math.pi),
     ]
     self.end_poses = [
         to_pose(-8.163, -1.7, math.pi),
         to_pose(-4.168, -1.7, math.pi),
         to_pose(-6.062 - 1, 0.248, -1.178),
     ]
     self.waypoints = [
         [
             geometry.Translation2d(-7.077, -1.7),
             geometry.Translation2d(-7.992, -1.7),
         ],
         [],
         [],
     ]
     self.expected_balls = [3, 0, 2]
     self.reversed = [False, True, False]
     self.trajectory_config = trajectory.TrajectoryConfig(maxVelocity=2.5,
                                                          maxAcceleration=1)
     self.trajectory_max = 3
     super().setup()
 def setup(self):
     # TODO add correct headings
     # empty waypoints are used for trajectories with only two points
     self.start_poses = [
         to_pose(-3.459, -1.7, math.pi),
         to_pose(-6.165, 0.582, 0),
         to_pose(-4.698, 2.359, 0),
     ]
     self.end_poses = [
         to_pose(-6.179, 2.981, 0),
         to_pose(-4.698, 2.359, 0),
         to_pose(-8.163, 0.705, 0),
     ]
     self.waypoints = [
         [
             geometry.Translation2d(-4.971, 1.154),
             geometry.Translation2d(-5.616, 1.978),
         ],
         [],
         [geometry.Translation2d(-5.668, 0.988)],
     ]
     self.trajectory_config = trajectory.TrajectoryConfig(maxVelocity=1.5,
                                                          maxAcceleration=1)
     self.expected_balls = [5, 0, 3]
     self.reversed = [False, True, False]
     self.trajectory_max = 3
     super().setup()
 def __init__(self) -> None:
     super().__init__()
     self.controller = controller.RamseteController()
     tolerance = to_pose(0.1, 0.1, math.pi / 18)
     self.controller.setTolerance(tolerance)
     self.trajectory_config = trajectory.TrajectoryConfig(maxVelocity=1,
                                                          maxAcceleration=1)
     self.gen = trajectory.TrajectoryGenerator()
     self.trajectory_num = 0
 def setup(self):
     self.start_poses = [to_pose(0, 0, math.pi)]
     self.end_poses = [to_pose(-2, 0, math.pi)]
     self.waypoints = [[geometry.Translation2d(-1, math.pi)]]
     self.trajectory_config = trajectory.TrajectoryConfig(maxVelocity=1,
                                                          maxAcceleration=1)
     self.expected_balls = [0]
     self.reversed = [False]
     self.trajectory_max = 1
     super().setup()
 def setup(self):
     self.start_poses = [to_pose(-3.459, -1.7, math.pi)]
     self.end_poses = [to_pose(-5.459, -1.7, math.pi)]
     self.waypoints = [[]]
     self.expected_balls = [0]
     self.reversed = [False]
     self.trajectory_config = trajectory.TrajectoryConfig(maxVelocity=2.5,
                                                          maxAcceleration=1)
     self.trajectory_max = 1
     super().setup()
 def setup(self):
     self.start_poses = [to_pose(-3.459, -1.7, math.pi)]
     self.end_poses = [to_pose(-8.163, -1.7, math.pi)]
     self.waypoints = [[
         geometry.Translation2d(-7.077, -1.7),
         geometry.Translation2d(-7.992, -1.7)
     ]]
     self.expected_balls = [3]
     self.reversed = [False]
     self.trajectory_config = trajectory.TrajectoryConfig(maxVelocity=2.5,
                                                          maxAcceleration=1)
     self.trajectory_max = 1
     super().setup()