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

Update Trajectory State to support Choreo moduleForces #725

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
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
Expand Up @@ -326,7 +326,18 @@ public static PathPlannerPath fromChoreoTrajectory(String trajectoryName) {
double xVel = ((Number) sample.get("velocityX")).doubleValue();
double yVel = ((Number) sample.get("velocityY")).doubleValue();
double angularVelRps = ((Number) sample.get("angularVelocity")).doubleValue();

JSONArray moduleForcesXArray = (JSONArray) sample.get("moduleForcesX");
List<Double> moduleForcesX = new ArrayList<>();
for (Object force : moduleForcesXArray) {
moduleForcesX.add(((Number) force).doubleValue());
}
state.moduleForcesX = Optional.of(moduleForcesX);
JSONArray moduleForcesYArray = (JSONArray) sample.get("moduleForcesY");
List<Double> moduleForcesY = new ArrayList<>();
for (Object force : moduleForcesYArray) {
moduleForcesY.add(((Number) force).doubleValue());
}
state.moduleForcesY = Optional.of(moduleForcesY);
state.timeSeconds = time;
state.linearVelocity = Math.hypot(xVel, yVel);
state.pose = new Pose2d(new Translation2d(xPos, yPos), new Rotation2d(rotationRad));
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
package com.pathplanner.lib.trajectory;

import java.util.List;
import java.util.Optional;

import com.pathplanner.lib.path.PathConstraints;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
Expand All @@ -17,7 +20,10 @@ public class PathPlannerTrajectoryState {
public Pose2d pose = Pose2d.kZero;
/** The linear velocity at this state in m/s */
public double linearVelocity = 0.0;

/** Optional module forces in the X direction in N on each module. Module forces appear in the following order: [FL, FR, BL, BR]. Will only be provided for Choreo paths*/
public Optional<List<Double>> moduleForcesX = Optional.empty();
/** Optional module forces in the Y direction in N on each module. Module forces appear in the following order: [FL, FR, BL, BR]. Will only be provided for Choreo paths*/
public Optional<List<Double>> moduleForcesY = Optional.empty();
// Values used only during generation, these will not be interpolated
/** The field-relative heading, or direction of travel, at this state */
protected Rotation2d heading = Rotation2d.kZero;
Expand Down