Puckinator Software Overview: Source Code
First, OpenCV transforms the frames from the camera to correct any distortion. The puck’s location is determined once this transformation is complete. The puck’s movement is tracked by predict_trajectory, which finds the optimal position for the striker to move to and the velocity vector of the puck. The stepper motor angles necessary for the striker to reach the position are calculated by coordinate_converter(). In the main loop, the optimal position and velocity vector are visualized on top of the OpenCV transformation and the angles are sent over serial to the firmware.
            Camera Capture: 
            Our camera provides a 640x400 monochrome video stream in the MJPG
            format. We use the imutils.video module to put the
            OpenCV video stream on a separate thread. This allows us to avoid
            using the blocking stream.read() function on the main
            thread that also is responsible for trajectory prediction and
            sending commands to the Arduino.
          
            Perspective Correction and Calibration: 
            When the program starts, the camera view is approximately centered
            on the air hockey table, but there is some perspective distortion.
            To find the location of the puck with relation to the table, we need
            to perspective correct and crop the frame to the corners of the
            table. The corners are marked with ArUco markers and their positions
            are identified through the cv.aruco
            module. For each marker, we define a desired position within the
            transformed frame. Those positions correspond to the actual
            dimensions of the air hockey table (multiplied by the
            PIXELS_PER_INCH constant). The detected corners (from
            the ArUco markers) and desired corners are passed into the
            cv.getPerspectiveTransform() function which calculates
            the transformation matrix between the distorted webcam frame and the
            desired points.
          
            On each new webcam frame, we call
            cv.warpPerspective() with the calculated transformation
            matrix to transform and crop the incoming image.
          
            Puck Detection 
Once we have a perspective corrected
            frame, the next step is to detect the puck using the ArUco marker
            that’s taped onto it. We use the same
            detectMarkers() function from the
            cv.aruco module. Using those results, we draw the
            detected markers on the frame for visualization purposes. To find
            the puck, we filter the results to only look for a marker with the
            ID 4 (which is the ID of the marker taped to the puck). If there are
            any such results, we then find the center point of the puck by
            calculating the average position of all four corners. The data is
            returned in an instance of the
            TimestampedPosition dataclass which stores the position
            and timestamp when the marker detection completed.
          
            In our main loop, we track the puck’s coordinate and timestamp at
            every frame and store it in an instance of the dataclass
            TimestampedPos , which has member variables x, y, and
            timestamp. In a while loop, we continually create new instances of
            TimestampedPos at every new frame, making sure to store
            one past instance of TimestampedPos each time.
          
                The function predict_trajectory then receives a
                previous_position, a latest_position,
                and a constant x_intercept to calculate the
                velocity vector of the puck using the change in time and change
                in position. HITTING_POSITION represents the
                arbitrarily set x-value for which the robot will attempt to meet
                the puck. It also calculates the line that the velocity vector
                falls on, hereafter referenced as the velocity line. Once this
                vector is defined, there are three modes for the robot’s
                behavior: copying, puck not bouncing, and puck bouncing. These
                all output y_int, which is the y-coordinate of the
                desired position of the striker.
              
                    If the puck is headed away from the robot (i.e. change in
                    position is positive), has a speed less than a specified
                    SPEED_THRESHOLD, or is traveling parallel to
                    the y-axis, it simply copies the y-position of the puck and
                    outputs no velocity vector. If none of the listed conditions
                    are fulfilled, it moves on to two more options as detailed
                    below.
                  
                    If the intersection between the velocity line and the
                    HITTING_POSITION is within the table’s bounds
                    (in other words, it will not bounce before the robot tries
                    to hit it), the function returns the y-value of the
                    intersection.
                  
                    If it is projected to hit the side of the table before
                    reaching HITTING_POSITION:
                    predict_next_bounce() takes in the slope and
                    y-intercept of the velocity line. It then outputs a
                    predicted velocity line for after the bounce as well as the
                    point at which the puck should bounce. This is done using
                    the law of reflection, or the concept that the angle of
                    incidence will equal the angle of reflection. Since we have
                    lines rather than angles, we did this by negating the slope
                    and calculating the new y-intercept using simple point-slope
                    form. We determined which of the two walls (we only
                    calculated bounces off of the long sides of the table) that
                    the puck would hit based off the sign of the slope. We then
                    stored the velocity lines at each bounce point in a list,
                    which was outputted by the outer function
                    predict_trajectory().
                  
            Aside from the velocity lines list, the function also outputs an
            instance of the dataclass TrajectoryPrediction, which
            includes the predicted x-position of the puck, the predicted
            y-position, the change in x, the change in y, and the predicted time
            that the puck will arrive at predicted position.
          
predict_trajectory():
          Interestingly, the real world behavior of the puck did not perfectly match the law of reflection, possibly due to uneven air distribution from the table, the table being tilted, and friction on the surface, which contributed to jitteriness in the outputted y. To reduce this jitteriness, we manually limited number of bounces that the function would predict to 2.
Visualizations:
            The velocity vector is displayed when the puck is not predicted to
            hit the side of the table before reaching the robot. If the puck
            bounces, it instead displays all of the velocity lines with
            directional arrows as limited by the edges of the table. A red
            circle is displayed around the point that the striker should move to
            to meet the puck. These are all drawn on top of the perspective
            transform that appears once the transformation is initiated with the
            “c” key. All of the visualization code lives outside
            predict_trajectory() in the main function.
          
Pictured above is an abstracted diagram of our five bar linkage. Point P represents the center of the striker, while sides A through D represent the arms of the linkage. (0, 0) in the inverse kinematics coordinate frame is the center of the left stepper motor shaft, while (0, 0) in the OpenCV coordinate frame is the upper left corner of the upper left ArUco Marker affixed to the table. Angles theta and phi represent the required angles of our two stepper motors to move the striker to point P.
            Coordinate Conversion: 
In the file
            puckinator.py, a separate function
            predict_trajectory()
            determines the desired OpenCV y-position of the striker based on the
            behavior of the puck. The OpenCV x-position of the striker is set as
            a constant at all times, meaning the striker should only move side
            to side along the defined x-position.
          
            The function coordinate_converter() takes in a point
            in the inverse kinematics coordinate frame and outputs the
            angles theta and phi required to move the striker to that point. In
            every other function we only use the OpenCV coordinate frame. To
            convert from the OpenCV coordinate found by predict
            trajectory() to the inverse kinematics coordinate
            frame, we add
            Y_OFFSET
            to the inverse kinematics y-value and feed it into the coordinate
            converter as the x-position, because the x and y axes are switched.
            Similarly, we add X_OFFSET to the desired inverse
            kinematics x-value and feed it as the y-position.
          
            Rectangular to Angular: 
Theta:
            \[\text{diag1} = \sqrt{x^2 + x^y}\]
            
            The bottom angle of isosceles triangle, which I will call angle b,
            is defined by sides A, B and diag1. Realizing that A and B are both
            length L, the law of cosines therefore states: \[L^2 = L^2 +
            \text{diag1}^2 - 2L\text{diag1} \cos(b)\] \[b =
            \cos^{-1}\left(\frac{\text{diag1}}{2L}\right)\] From this, we
            conclude that: \[\theta = \tan^{-1}\left(\frac{y}{x}\right) +
            \cos^{-1}\left(\frac{\text{diag1}}{2L}\right)\]
            
            
Phi:
            \[\text{diag2} = \sqrt{(s - x)^2 + y^2}\]
            
            Angle c of the isosceles triangle defined by C, D, and diag2 can
            also be defined by law of cosines: \[c =
            \cos^{-1}\left(\frac{\text{diag2}}{2L}\right)\] 
From this it
            follows: \[\phi = \pi -
            \left(\cos^{-1}\left(\frac{\text{diag2}}{2L}\right) +
            \tan^{-1}\left(\frac{y}{s - x}\right)\right)\] 
            These equations apply for when x > 0. However in the code
            implementation, we used the numpy function arctan2() so
            that the angle contributions of the two triangles defined by x, y
            and diag1 and by x, y, and diag 2 respectively would continue to
            function when point P had a negative x value. When the x value of
            the striker becomes negative, the right triangles mentioned
            previously flip vertically. For this reason, the arctangent
            calculation must be subtracted by 90 to get the new desired angle
            contribution. arctan2() does this automatically, hence
            its inclusion in the arctangent calculations within
            coordinate_converter(). For cases in which x = 0, we
            simply set x = 0.001 to avoid zero division errors.
          
            Once predict_trajectory() and
            coordinate_converter() have done their jobs finding the
            best theta and phi values for the arm to move to based on the puck’s
            behavior, we must send these values over serial to our Arduino,
            which is responsible for turning those values into real-world motor
            movement. Once we initialize the arduino with a high baud rate to
            reduce latency and a write timeout to protect against overloading
            the queue, this is as simple as using the serial method
            write() to transfer those theta and phi values over.
            The inputs are adjusted by 90 degrees because the stepper motors are
            zeroed at 90 degrees (As explained in the Firmware section).
          
Our external python dependecies are listed in the requirements.txt file found on our github. They include OpenCV, NumPy, pySerial, time, math, datclasses, imutils, and the Arduino library FlexyStepper.