Introduction
I’ve seen a lot of whitepapers on Shooting On The Fly (I wrote a LaTeX paper on it once), but they often get bogged down in formal kinematics notation that makes high schoolers’ eyes glaze over. Instead of sending it for the 50th time, I wanted to try to break it down to the level where you can actually code it, while also covering the messy real world dynamics I heard to learn the hard way.
The Concept: It’s Just Vectors
At its core, SOTF is a vector addition problem.
Imagine you are standing still and throwing a ball at a target. Easy, right? You aim directly at it. Now, imagine you are running sideways past the target. If you aim directly at the target, the ball carries your sideways momentum and misses wide. To hit the target, you have to aim backwards to cancel out your own movement.
In robot terms:
V_ball/ground = V_ball/robot + V_robot/ground
- Ball_Velocity_Ground: The vector the ball travels relative to the field (This needs to point at the goal!).
- Ball_Velocity_Robot: The vector the ball leaves your robot (What you control: Turret angle, Shooter RPM/Pitch).
- Robot_Velocity_Ground: The vector your robot is moving (What your odometry tells you).
We know where we want the ball to go (the goal). We know how we are moving. We need to solve for Ball_Velocity_Robot.
Rearranging the equation:
V_ball/robot = V_ball/ground - V_robot/ground
That’s it. That’s the math. The rest is just implementation details and handling the fact that the real world hates theory.
What's happening:
- Move your mouse to control the robot position
- The green vector shows your robot's current velocity
- The red dashed vector shows where you'd aim if standing still (misses if moving!)
- The orange vector shows the compensated aim that accounts for motion
- Click to fire both shots and see the difference!
Prerequisites
Before you try to implement this, you need three things:
- A Consistent Shooter: If your shooter varies by ±10% RPM shot-to-shot while standing still, no amount of math will save you while moving.
- Reliable Odometry: You need to know your robot’s velocity vector relative to the field. For FTC, deadwheel odometry is practically mandatory. For FRC, swerve encoders or a good pose estimator are usually sufficient (apriltags!).
- Target Tracking: You need to know where the goal is. Limelight, PhotonVision, or just really good field-relative odometry.
The Math Implementation
Let’s break this down into steps you can actually write code for.
Step 1: Get your Vectors
First, define your Goal Vector. This is the vector from your robot to the goal.
Let’s say the goal is at (Goal_X, Goal_Y) and you are at (Robot_X, Robot_Y).
double targetX = Goal_X - Robot_X;
double targetY = Goal_Y - Robot_Y;
Translation2d targetPosition = new Translation2d(targetX, targetY);
// Calculate the ideal exit velocity magnitude (based on distance)
double distance = targetPosition.getNorm();
double idealSpeed = getShooterSpeedForDistance(distance);
Translation2d targetVector = targetPosition.div(distance).times(idealSpeed); Note: getShooterSpeedForDistance comes from your tuning map of “Distance vs RPM/Pitch”.
Next, get your Robot Velocity Vector. From your odometry system:
Translation2d robotVelocity = new Translation2d(vel_x, vel_y); // Field centric velocity! Step 2: The Subtraction
Now we apply our golden rule:
V_shot = V_target - V_robot
Translation2d shotVector = targetVector.minus(robotVelocity); Step 3: Convert to Controls
Now shotVector represents the direction and speed the ball needs to leave your robot relative to the chassis.
- Turret Angle: The angle of this vector is where your turret should point (relative to the field).
- Shooter Power: The magnitude of this vector is the speed the ball needs to have.
double turretAngle = shotVector.getAngle().getDegrees();
double requiredSpeed = shotVector.getNorm();
// OPTION 1: Variable Flywheel Speed (Fixed Hood)
// double shooterRPM = calcRPM(requiredSpeed);
// OPTION 2: Variable Hood Angle (Constant Speed)
// double constantTotalSpeed = 15.0; // m/s
// double newPitch = Math.acos(requiredSpeed / constantTotalSpeed);
// NOTE: For high-arc shots (like Rapid React or Rebuilt), `idealSpeed` MUST be the
// horizontal component of the exit velocity, NOT the total speed (RPM).
// If your lookup table gives total speed/RPM, you must project it:
// idealSpeed_Horizontal = Total_Speed * cos(release_angle); Wait, The Shooter Speed Changed?
Yes! This is a common “aha” moment. If you are driving towards the goal, your robot is helping the ball, so you don’t need to shoot as hard. If you are driving away, you need to shoot harder to overcome your backward momentum.
Moving Hood Variant: If you have a constant speed flywheel and a moving hood, the physics are slightly different. Instead of changing the shot speed, you change the exit angle to get the required horizontal velocity. If you need more horizontal velocity (driving away), you lower the hood (shoot flatter). If you need less horizontal velocity (driving towards), you raise the hood (shoot higher).
Handling “Lobbed” Shots
This is a common pitfall. If you are shooting a high-arc shot (e.g. 60-70 degree exit angle), you must be careful with your vector math.
The math above assumes a 2D plane. If you use your total shooter exit velocity (RPM) as the vector magnitude, you will massively overcompensate for robot motion.
Why? Gravity only affects the vertical velocity. The robot’s motion only affects the horizontal velocity. For a high lob, your horizontal velocity is very small (maybe 4 m/s), even if your ball is leaving the shooter at 12 m/s. If your robot is moving at 2 m/s, that’s 50% of your horizontal velocity!
The Fix:
- Decompose your shot into Horizontal and Vertical components.
v_horiz = v_total * cos(theta_pitch)
v_vert = v_total * sin(theta_pitch)
v_horiz_robot = v_horiz_ground - v_robot - Recombine to get the new total exit velocity.
v'_total = sqrt(v_horiz_robot^2 + v_vert^2)
theta'_pitch = arctan(v_vert / v_horiz_robot) If you have a constant speed shooter (Option 2 above):
You can’t change New_V_total. Instead, you solve for New_Pitch such that the horizontal component matches V_horizontal_robot.
theta’_pitch = arccos(v_horiz_robot / v_total)
Warning: Changing the pitch changes the vertical velocity, which changes the flight time, which changes the required horizontal velocity. For small corrections, this single-step calculation is usually “good enough”, but perfect accuracy might require an iterative solver.
The “Real World” Dynamics (Where things go wrong)
If you implement the math above, you’ll get close. But you’ll probably still miss. Why? Because physics is mean. Here are the artifacts you need to account for.
1. Latency Compensation (The Time Travel Problem)
Your camera takes a picture. It takes 10ms to process. It sends the data to the Rio/Control Hub (another 5ms). Your loop calculates the turret angle. You send the command. The turret motor takes time to accelerate.
By the time the ball actually leaves the robot, you are in a different place than when you took the picture.
The Fix: Project your position forward.
double latencySeconds = CAMERA_LATENCY + MOTOR_LAG + SHOOTING_TIME;
Translation2d futurePos = currentPos.plus(robotVelocity.times(latencySeconds));
// Now calculate your target vector from futurePos, not currentPos You will need to tune latencySeconds. It’s often higher than you think (sometimes 100-200ms or more depending on the system).
2. Shooter Wheel Dynamics (The “Squish” Factor)
When a ball touches a flywheel, two things happen:
- The wheel slows down (momentum transfer).
- The wheel slips against the ball.
The vector math assumes the ball leaves at the “commanded” velocity. It doesn’t. It leaves at the actual surface speed of the wheel minus slip.
Variable Velocity Artifact:
Remember how the math changes the required shooter speed based on robot motion?
If you are driving away from the goal, the math demands higher RPM.
Higher RPM = More slip = Different trajectory.
You might need a 2D lookup table: Map<Distance, RobotVelocity> -> RPM, or simply tune your RPM function to account for the fact that effectiveness drops at higher speeds.
Recovery Time: If you are shooting a rapid stream of balls while moving, the first one might go in, but the impact slows the wheel down. If your PID isn’t aggressive enough, the second shot will be too slow and fall short.
- Fix: Use a Feedforward-heavy controller (BangBang or aggressive Kv).
- Advanced Fix: If you know the RPM has dropped, delay the feeder until it recovers, OR dynamically adjust the hood angle/pitch to compensate for the lower velocity (if you have an adjustable hood).
3. The “Magnus Effect” and Air Resistance
Calculated SOTF vectors usually assume a parabolic vacuum trajectory. If your game piece is a foam ball (FTC/FRC standard), it has air resistance and spin.
Sideways Motion: If you are moving sideways, you impart sideways spin on the ball relative to the air. This can cause the ball to curve (Magnus effect).
Drag: Driving towards the goal effectively increases the air speed over the ball, increasing drag.
The Fix: This is hard to model perfectly. The easiest solution is usually an empirical “correction factor”.
theta_adjusted = theta_calculated + (k * v_transverse) Tune k until it goes straight.
4. Centripetal Forces (Turret Whip)
If your turret is at the end of a long robot arm or you are spinning the robot chassis fast, the turret itself has a tangential velocity. If your robot is spinning at 180 degrees/sec and your turret is 10 inches from the center of rotation, the turret tip is moving at ~30 inches/sec. Add this velocity to your robot velocity vector before doing the subtraction.
Putting it All Together
Here is a simplified “end-to-end” example of what the update loop might look like in a real robot codebase.
public class SuperShooter {
public void update(Pose2d robotPose, ChassisSpeeds robotSpeed) {
// 1. LATENCY COMP
double latency = 0.15; // Tuned constant
Translation2d futurePos = robotPose.getTranslation().plus(
new Translation2d(robotSpeed.vxMetersPerSecond, robotSpeed.vyMetersPerSecond).times(latency)
);
// 2. GET TARGET VECTOR
Translation2d goalLocation = FieldConstants.GOAL_LOCATION;
Translation2d targetVec = goalLocation.minus(futurePos);
double dist = targetVec.getNorm();
// 3. CALCULATE IDEAL SHOT (Stationary)
// Note: This returns HORIZONTAL velocity component
double idealHorizontalSpeed = ShooterTable.getSpeed(dist);
// 4. VECTOR SUBTRACTION
Translation2d robotVelVec = new Translation2d(robotSpeed.vxMetersPerSecond, robotSpeed.vyMetersPerSecond);
Translation2d shotVec = targetVec.div(dist).times(idealHorizontalSpeed).minus(robotVelVec);
// 5. CONVERT TO CONTROLS
double turretAngle = shotVec.getAngle().getDegrees();
double newHorizontalSpeed = shotVec.getNorm();
// 6. SOLVE FOR NEW PITCH/RPM
// Assuming constant total exit velocity, variable hood:
double totalExitVelocity = 15.0; // m/s
// Clamp to avoid domain errors if we need more speed than possible
double ratio = Math.min(newHorizontalSpeed / totalExitVelocity, 1.0);
double newPitch = Math.acos(ratio);
// 7. SET OUTPUTS
turret.setAngle(turretAngle);
hood.setAngle(Math.toDegrees(newPitch));
shooter.setRPM(calcRPM(totalExitVelocity));
}
} And finally, because seeing is believing, here is a clip of this logic in action: