Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Swerve simple trajectory update #485

Merged
merged 33 commits into from
Jan 18, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
554bd97
FRCRobotTemplate SCL update
Rongrrz Oct 5, 2024
1e7f69f
End of day 10/19
Rongrrz Oct 19, 2024
8103d99
End of day 10/26
Rongrrz Oct 26, 2024
060ac33
Node map approach
Rongrrz Nov 2, 2024
ce1e830
Checkstyle fix
Rongrrz Nov 2, 2024
da0210e
End of day 11/02/2024
Rongrrz Nov 2, 2024
bba39e9
Removing constant velocity
Rongrrz Nov 6, 2024
574d595
Remove constant velocity
Rongrrz Nov 6, 2024
ea9d1a0
Merge branch 'SwerveSimpleTrajectory-update' of https://github.com/Te…
Rongrrz Nov 6, 2024
36780b0
Revert "Merge branch 'SwerveSimpleTrajectory-update' of https://githu…
Rongrrz Nov 9, 2024
f57a390
Revert "Remove constant velocity"
Rongrrz Nov 9, 2024
e20c1cc
Working swerve with acceleration values
Rongrrz Nov 9, 2024
0815995
Duration fix
Rongrrz Nov 9, 2024
5068235
Merge branch 'main' into SwerveSimpleTrajectory-update
Rongrrz Nov 9, 2024
b9fc3c4
Deleted unnecessary comments
Rongrrz Nov 9, 2024
875b299
Added kinematics mode to SwerveSimpleTrajectoryCommand
Rongrrz Nov 11, 2024
ef80d5d
Temporary checkstyle fix
Rongrrz Nov 12, 2024
5dec0d3
Simplified kinematic values into a class
Rongrrz Nov 16, 2024
e5935fb
Swerve global kinematics mode
Rongrrz Nov 16, 2024
036939c
Tests for SwerveKinematicsCalculator
Rongrrz Nov 23, 2024
41d39bc
Minimize deceleration time
Rongrrz Nov 27, 2024
02e825b
End of day 12/07
Rongrrz Dec 7, 2024
0323dd2
Kinematics bug fix
Rongrrz Jan 7, 2025
8eaae26
Clean up
Rongrrz Jan 8, 2025
b9595f2
Resolving PR comments part 1
Rongrrz Jan 10, 2025
4528eef
Fixed overshooting bug
Rongrrz Jan 11, 2025
d9086d2
Checkstyle fix
Rongrrz Jan 11, 2025
0aee6f3
RobotAssertionManager and clean up
Rongrrz Jan 11, 2025
0058b8a
Uncommented calculator test
Rongrrz Jan 12, 2025
0bc34bc
More edge case checks
Rongrrz Jan 12, 2025
bfaa83f
Merge branch 'main' into SwerveSimpleTrajectory-update
Rongrrz Jan 15, 2025
9fd33d1
Merge branch 'main' into SwerveSimpleTrajectory-update
JohnGilb Jan 17, 2025
ea0527b
Merge branch 'main' into SwerveSimpleTrajectory-update
JohnGilb Jan 18, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
package xbot.common.subsystems.drive;


/**
* @param operationEndingVelocity m/s, velocity we end at
* @param operationAcceleration mls^2, acceleration to go at
* @param operationTime Time in seconds
*/ // SwerveCalculatorNode are small little steps to be interpreted and formed together
//to create a path to be used for the SwerveKinematicsCalculator
public record SwerveCalculatorNode(double operationTime, double operationAcceleration, double operationEndingVelocity) {

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,288 @@
package xbot.common.subsystems.drive;

import org.apache.logging.log4j.LogManager;
import org.apache.logging.log4j.Logger;
import xbot.common.logging.RobotAssertionManager;

import java.util.ArrayList;
import java.util.List;

public class SwerveKinematicsCalculator {

/*
The SwerveKinematicsCalculator is designed to compute the motion of a swerve drive system from a starting position
and velocity to a goal position and velocity. It takes into account parameters like maximum acceleration,
goal velocity, and maximum velocity to generate a sequence of motion stages, ensuring precise path planning
and execution.

(Breaks an XbotSwervePoint down into smaller nodes containing time, velocity, and acceleration)
Note: goal velocity may not always be reached, but in such case will be as close as possible.

Code involving the quadratic formula IS NOT ROBUST (since only this script uses them as of currently)
*/

final double startPosition;
final double endPosition;
final double acceleration;
final double initialVelocity;
final double goalVelocity;
final double maxVelocity;
final List<SwerveCalculatorNode> nodeMap;
RobotAssertionManager assertionManager;

// Returns the x-intercepts of a quadratic equation
private static List<Double> quadraticFormula(double a, double b, double c) {
double squareRootResult = Math.sqrt(Math.pow(b, 2) - (4 * a * c));
double result1 = (-b + squareRootResult) / (2 * a);
double result2 = (-b - squareRootResult) / (2 * a);

List<Double> results = new ArrayList<>();
results.add(result1);
results.add(result2);
return results;
}

public static double calculateTimeToGoalPosition(double acceleration, double initialVelocity,
double initialPosition, double goalPosition) {
double a = 0.5 * acceleration;
double b = initialVelocity;
double c = initialPosition - goalPosition;
if (acceleration == 0) {
return (-c/b);

} else if (acceleration > 0) {
List<Double> result = quadraticFormula(a, b, c);
return Math.max(result.get(0), result.get(1));

} else {
List<Double> result = quadraticFormula(-a, -b, -c);
return Math.min(result.get(0), result.get(1));

}
}

public SwerveKinematicsCalculator(RobotAssertionManager assertionManager, double startPosition, double endPosition,
SwervePointKinematics kinematics) {
this.assertionManager = assertionManager;
// Gimmicky way to avoid division by zero and to deal with human code-error
Rongrrz marked this conversation as resolved.
Show resolved Hide resolved
if (endPosition - startPosition == 0) {
assertionManager.throwException("Calculator instantiated for same start and end position", new Exception());
endPosition += 0.01;
}

this.startPosition = startPosition;
this.endPosition = endPosition;
this.acceleration = kinematics.acceleration;
this.initialVelocity = kinematics.initialVelocity;
this.goalVelocity = kinematics.goalVelocity;
this.maxVelocity = kinematics.maxVelocity;

// Likely need to validate the above values to prevent bad stuff
nodeMap = generateNodeMap();
}

// Based off of given value, initialize the proper path, store notes in a list, and be prepared to output values
// (If velocity gets to negative we are *KINDA* cooked)
public List<SwerveCalculatorNode> generateNodeMap() {
List<SwerveCalculatorNode> nodeMap = new ArrayList<>();
double leftoverDistance = endPosition - startPosition;

double currentVelocity = initialVelocity;

// Deceleration
if (currentVelocity > goalVelocity) {
// Cruise as much as possible, then decelerate
double decelerateToGoalVelocityTime = (goalVelocity - currentVelocity) / -acceleration;
double distanceNeededToDecelerate = 0.5 * (currentVelocity + goalVelocity) * decelerateToGoalVelocityTime;

double distanceExcludingDeceleration = leftoverDistance - distanceNeededToDecelerate;

if (distanceExcludingDeceleration > 0) {
double halfDistance = distanceExcludingDeceleration / 2;
double timeForHalf = calculateTimeToGoalPosition(acceleration, currentVelocity, 0, halfDistance);
double peakVelocity = currentVelocity + acceleration * timeForHalf;

if (peakVelocity <= maxVelocity) {
// Add two nodes, accelerate to peak, decelerate to goal
nodeMap.add(new SwerveCalculatorNode(timeForHalf, acceleration, peakVelocity));
nodeMap.add(new SwerveCalculatorNode(timeForHalf, -acceleration, currentVelocity));
} else {
// Going to peak will not work as it will exceed our maximumVelocity limit
// Go to max, then cruise, then decelerate
double timeFromCurrentToMaxV = (maxVelocity - currentVelocity) / acceleration; // Rename
double initialPosition = (endPosition - startPosition) - leftoverDistance;
double finalPositionAfterAcceleration = 0.5 * (currentVelocity + maxVelocity) * timeFromCurrentToMaxV + initialPosition;
double positionDelta = finalPositionAfterAcceleration - initialPosition;
double cruiseDistance = distanceExcludingDeceleration - (positionDelta * 2);
double cruiseTime = cruiseDistance / maxVelocity;

nodeMap.add(new SwerveCalculatorNode(timeFromCurrentToMaxV, acceleration, maxVelocity));
nodeMap.add(new SwerveCalculatorNode(cruiseTime, 0, maxVelocity));
nodeMap.add(new SwerveCalculatorNode(timeFromCurrentToMaxV, -acceleration, currentVelocity));
}

nodeMap.add(new SwerveCalculatorNode(decelerateToGoalVelocityTime, -acceleration, goalVelocity));

} else {
// Decelerate as much as possible
double decelerationTime = calculateTimeToGoalPosition(-acceleration, currentVelocity, 0, leftoverDistance);
nodeMap.add(new SwerveCalculatorNode(
decelerationTime,
-acceleration,
currentVelocity - acceleration * decelerationTime
));
}
return nodeMap;
}

// Acceleration
if (currentVelocity < goalVelocity) {
double initialToGoalVelocityTime = (goalVelocity - currentVelocity) / acceleration;
double operationDistance = currentVelocity * initialToGoalVelocityTime
+ 0.5 * acceleration * Math.pow(initialToGoalVelocityTime, 2);

if (operationDistance >= leftoverDistance) {
// No matter how much you accelerate you won't reach goal velocity before distance...
// ...so we accelerate til the end!
double time = calculateTimeToGoalPosition(acceleration, currentVelocity, 0, leftoverDistance);
nodeMap.add(new SwerveCalculatorNode(
time,
acceleration,
currentVelocity + acceleration * time
));
return nodeMap;
} else {
// Accelerate to goal velocity
nodeMap.add(new SwerveCalculatorNode(initialToGoalVelocityTime, acceleration, goalVelocity));
leftoverDistance -= operationDistance;
currentVelocity = goalVelocity;
}
}

// STEP 2: If not at max velocity, build an accelerate->cruise>decelerate nodeMap
if (currentVelocity < maxVelocity) {
// Check /\ (vortex) does the job (or maybe its peak exceeds maxVelocity)
Rongrrz marked this conversation as resolved.
Show resolved Hide resolved
// if not then we need to add a cruising part: /---\ (looks like this)
double halfDistance = leftoverDistance / 2;
double timeForHalf = calculateTimeToGoalPosition(acceleration, currentVelocity, 0, halfDistance);

// Figure out end velocity
double peakVelocity = currentVelocity + acceleration * timeForHalf;
if (peakVelocity <= maxVelocity) {
// Add two nodes, accelerate to peak, decelerate to goal
nodeMap.add(new SwerveCalculatorNode(timeForHalf, acceleration, peakVelocity));
nodeMap.add(new SwerveCalculatorNode(timeForHalf, -acceleration, goalVelocity));
} else {
// Going to peak will not work as it will exceed our maximumVelocity limit
// Go to max, then cruise, then decelerate
double timeFromGoalToMaxVelocity = (maxVelocity - currentVelocity) / acceleration;
double initialPosition = (endPosition - startPosition) - leftoverDistance;
double finalPositionAfterAcceleration = 0.5 * (currentVelocity + maxVelocity)
* timeFromGoalToMaxVelocity + initialPosition;
double positionDelta = finalPositionAfterAcceleration - initialPosition;
double cruiseDistance = leftoverDistance - (positionDelta * 2);
double cruiseTime = cruiseDistance / maxVelocity;

nodeMap.add(new SwerveCalculatorNode(timeFromGoalToMaxVelocity, acceleration, maxVelocity));
nodeMap.add(new SwerveCalculatorNode(cruiseTime, 0, maxVelocity));
nodeMap.add(new SwerveCalculatorNode(timeFromGoalToMaxVelocity, -acceleration, goalVelocity));
}
return nodeMap;

} else {
// Cruise til the end if we are at both goal & max velocity!
double cruiseTime = leftoverDistance / currentVelocity;
nodeMap.add(new SwerveCalculatorNode(
cruiseTime,
0,
currentVelocity
));
return nodeMap;
}
}

public List<SwerveCalculatorNode> getNodeMap() {
return nodeMap;
}

public double getVelocityAtFinish() {
SwerveCalculatorNode finalNode = nodeMap.get(nodeMap.size() - 1);
return finalNode.operationEndingVelocity();
}

public double getTotalOperationTime() {
double time = 0;
for (SwerveCalculatorNode node : this.nodeMap) {
time += node.operationTime();
}
return time;
}

public double getDistanceTravelledInMetersAtTime(double time) {
if (time < 0) {
assertionManager.throwException("Invalid time to getDistanceTravelledInMetersAtTime", new Exception());
return 0;
}
double elapsedTime = 0;
double totalDistance = 0;
double velocity = initialVelocity;
for (SwerveCalculatorNode node : this.nodeMap) {
// Get amount of time elapsed (no exceed time)
// Add distance with node
double operationTime = node.operationTime();
if ((time - (operationTime + elapsedTime)) >= 0) {
double distanceTravelled = velocity * operationTime
+ 0.5 * node.operationAcceleration() * Math.pow(operationTime, 2);

totalDistance += distanceTravelled;
velocity = node.operationEndingVelocity();
elapsedTime += node.operationTime();
} else {
// Find the amount of time we'll be using the node
operationTime = time - elapsedTime;
double distanceTravelled = velocity * operationTime
+ 0.5 * node.operationAcceleration() * Math.pow(operationTime, 2);
totalDistance += distanceTravelled;
break;
}
}
return totalDistance;
}

// Range: 0 - 1 (not in actual percentages!!!)
public double geDistanceTravelledAtCompletionPercentage(double percentage) {
double time = getTotalOperationTime() * percentage;
return getDistanceTravelledInMetersAtTime(time);
}

public double getTotalDistanceInMeters() {
return Math.abs(endPosition - startPosition);
}

public double getVelocityAtDistanceTravelled(double distanceTravelled) {
double totalDistanceTravelled = 0;
double currentVelocity = initialVelocity;
for (SwerveCalculatorNode node : this.nodeMap) {

// Find amount of distance current node travels
double operationDistance = (currentVelocity * node.operationTime()) + (0.5
* node.operationAcceleration()) * Math.pow(node.operationTime(), 2);

// Continue until we land on the node we stop in
if (distanceTravelled - (totalDistanceTravelled + operationDistance) >= 0) {
totalDistanceTravelled += operationDistance;
currentVelocity += (node.operationAcceleration() * node.operationTime());
} else {
// Accelerate the remaining distance
double operationTime = calculateTimeToGoalPosition(
node.operationAcceleration(),
currentVelocity,
totalDistanceTravelled,
distanceTravelled);
currentVelocity += (node.operationAcceleration() * operationTime);
break;
}
}
return currentVelocity;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
package xbot.common.subsystems.drive;

// Contains a set of kinematics values
public class SwervePointKinematics {
final double acceleration; // Units: m/s^2
final double initialVelocity; // Units: m/s
final double goalVelocity; // m/s, velocity you want to be when you reach your goal, may not always be fulfilled.
final double maxVelocity; // m/s

public SwervePointKinematics(double a, double initialVelocity, double goalVelocity, double maxVelocity) {
this.acceleration = a;
this.initialVelocity = initialVelocity;
this.goalVelocity = Math.max(Math.min(maxVelocity, goalVelocity), -maxVelocity);
this.maxVelocity = maxVelocity;
}

public SwervePointKinematics kinematicsWithNewVi(double newVi) {
return new SwervePointKinematics(acceleration, newVi, goalVelocity, maxVelocity);
}

public double getAcceleration() {
return this.acceleration;
}

public double getMaxVelocity() {
return this.maxVelocity;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import edu.wpi.first.math.geometry.Twist2d;
import xbot.common.command.BaseCommand;
import xbot.common.logging.RobotAssertionManager;
import xbot.common.math.XYPair;
import xbot.common.properties.PropertyFactory;
import xbot.common.subsystems.drive.control_logic.HeadingModule;
Expand All @@ -24,14 +25,14 @@ public class SwerveSimpleTrajectoryCommand extends BaseCommand {

@Inject
public SwerveSimpleTrajectoryCommand(BaseSwerveDriveSubsystem drive, BasePoseSubsystem pose, PropertyFactory pf,
HeadingModuleFactory headingModuleFactory) {
HeadingModuleFactory headingModuleFactory, RobotAssertionManager assertionManager) {
this.drive = drive;
this.pose = pose;
headingModule = headingModuleFactory.create(drive.getRotateToHeadingPid());

pf.setPrefix(this);
this.addRequirements(drive);
logic = new SwerveSimpleTrajectoryLogic();
logic = new SwerveSimpleTrajectoryLogic(assertionManager);
alternativeIsFinishedSupplier = () -> false;
}

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
package xbot.common.subsystems.drive;

/* Different ways to render the SwerveSimpleTrajectoryCommand's path */
public enum SwerveSimpleTrajectoryMode {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⭐ could you add more comments about what each mode does? What would you tell a new student that had to do use this about their choices?

ConstantVelocity, // We'll use a constant velocity throughout the course of our travel
DurationInSeconds, // Each point will be given a "duration"
KinematicsForIndividualPoints, // Each individual point will have its own kinematics values it'll go at
KinematicsForPointsList // One kinematics values for the entire route
}
Original file line number Diff line number Diff line change
Expand Up @@ -333,6 +333,7 @@ public void periodic() {
isNavXReady = true;
}
updatePose();
aKitLog.record("Heading", currentHeading.getDegrees());
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,14 @@

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import xbot.common.subsystems.drive.SwervePointKinematics;

public interface ProvidesInterpolationData {
public Translation2d getTranslation2d();

public double getSecondsForSegment();

public Rotation2d getRotation2d();

public SwervePointKinematics getKinematics();
}
Loading