Skip to content

Commit

Permalink
fix all java build warnings (#380)
Browse files Browse the repository at this point in the history
  • Loading branch information
mjansen4857 authored Oct 8, 2023
1 parent fd4dcf7 commit c3c3c0f
Show file tree
Hide file tree
Showing 35 changed files with 313 additions and 43 deletions.
1 change: 1 addition & 0 deletions pathplannerlib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,7 @@ spotless {
}

javadoc {
exclude 'org/json/simple/**'
options {
links 'https://docs.oracle.com/en/java/javase/11/docs/api/', 'https://github.wpilib.org/allwpilib/docs/release/java/'
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
import org.json.simple.JSONObject;
import org.json.simple.parser.JSONParser;

/** Utility class used to build auto routines */
public class AutoBuilder {
private static boolean configured = false;

Expand Down Expand Up @@ -279,6 +280,12 @@ public static Command followPathWithEvents(PathPlannerPath path) {
return new FollowPathWithEvents(pathFollowingCommandBuilder.apply(path), path, getPose);
}

/**
* Get the starting pose from its JSON representation. This is only used internally.
*
* @param startingPoseJson JSON object representing a starting pose.
* @return The Pose2d starting pose
*/
public static Pose2d getStartingPoseFromJson(JSONObject startingPoseJson) {
JSONObject pos = (JSONObject) startingPoseJson.get("position");
double x = ((Number) pos.get("x")).doubleValue();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,12 @@
package com.pathplanner.lib.auto;

/** An exception while building autos */
public class AutoBuilderException extends RuntimeException {
/**
* Create a new auto builder exception
*
* @param message Error message
*/
public AutoBuilderException(String message) {
super(message);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import org.json.simple.JSONArray;
import org.json.simple.JSONObject;

/** Utility class for building commands used in autos */
public class CommandUtil {
/**
* Wraps a command with a functional command that calls the command's initialize, execute, end,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import java.util.List;
import java.util.Map;

/** Utility class for managing named commands */
public class EventManager {
private static final HashMap<String, Command> eventMap = new HashMap<>();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Base command for following a path */
public class FollowPathCommand extends Command {
private final Timer timer = new Timer();
private final PathPlannerPath path;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Follow a path using a PPHolonomicDriveController */
public class FollowPathHolonomic extends FollowPathCommand {
/**
* Construct a path following command that will use a holonomic drive controller for holonomic
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Follow a path using a PPLTVController */
public class FollowPathLTV extends FollowPathCommand {
/**
* Create a path following command that will use an LTV unicycle controller for differential drive
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Follow a path using a PPRamseteController */
public class FollowPathRamsete extends FollowPathCommand {
/**
* Construct a path following command that will use a Ramsete path following controller for
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import java.util.function.Supplier;
import java.util.stream.Collectors;

/** Command that will run a path following command and trigger event markers along the way */
public class FollowPathWithEvents extends Command {
private final Command pathFollowingCommand;
private final PathPlannerPath path;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Pathfind and follow the path with a PPHolonomicDriveController */
public class PathfindHolonomic extends PathfindingCommand {
/**
* Constructs a new PathfindHolonomic command that will generate a path towards the given path.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Pathfind and follow the path with a PPLTVController */
public class PathfindLTV extends PathfindingCommand {
/**
* Constructs a new PathfindLTV command that will generate a path towards the given path.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Pathfind and follow the path with a PPRamseteController */
public class PathfindRamsete extends PathfindingCommand {
/**
* Constructs a new PathfindRamsete command that will generate a path towards the given path.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import java.util.function.Consumer;
import java.util.function.Supplier;

/** Base pathfinding command */
public class PathfindingCommand extends Command {
private final Timer timer = new Timer();
private final PathPlannerPath targetPath;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.trajectory.TrapezoidProfile;

/** Path following controller for holonomic drive trains */
public class PPHolonomicDriveController implements PathFollowingController {
private final PIDController xController;
private final PIDController yController;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import edu.wpi.first.math.numbers.N2;
import edu.wpi.first.math.numbers.N3;

/** LTV following controller */
public class PPLTVController extends LTVUnicycleController implements PathFollowingController {
private double lastError = 0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;

/** Ramsete path following controller */
public class PPRamseteController extends RamseteController implements PathFollowingController {
private double lastError = 0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;

/** Interface used by path following controllers */
public interface PathFollowingController {
/**
* Calculates the next output of the path following controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import java.util.Objects;
import org.json.simple.JSONObject;

/** A zone on a path with different kinematic constraints */
public class ConstraintsZone {
private final double minWaypointPos;
private final double maxWaypointPos;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import java.util.Objects;
import org.json.simple.JSONObject;

/** Position along the path that will trigger a command when reached */
public class EventMarker {
private final double waypointRelativePos;
private final Command command;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import java.util.Objects;
import org.json.simple.JSONObject;

/** Describes the goal end state of the robot when finishing a path */
public class GoalEndState {
private final double velocity;
private final Rotation2d rotation;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import java.util.Objects;
import org.json.simple.JSONObject;

/** Kinematic path following constraints */
public class PathConstraints {
private final double maxVelocityMps;
private final double maxAccelerationMpsSq;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import org.json.simple.JSONObject;
import org.json.simple.parser.JSONParser;

/** A PathPlanner path. NOTE: This is not a trajectory and isn't directly followed. */
public class PathPlannerPath {
private List<Translation2d> bezierPoints;
private List<RotationTarget> rotationTargets;
Expand Down Expand Up @@ -71,6 +72,11 @@ private PathPlannerPath(PathConstraints globalConstraints, GoalEndState goalEndS
this.allPoints = new ArrayList<>();
}

/**
* Hot reload the path. This is used internally.
*
* @param pathJson Updated JSONObject for the path
*/
public void hotReload(JSONObject pathJson) {
PathPlannerPath updatedPath = PathPlannerPath.fromJson(pathJson);

Expand Down Expand Up @@ -192,22 +198,7 @@ public PathConstraints getConstraintsForPoint(int idx) {
return globalConstraints;
}

/**
* Create a path planner path from pre-generated path points. This is used internally, and you
* likely should not use this
*/
public static PathPlannerPath fromPathPoints(
List<PathPoint> pathPoints, PathConstraints globalConstraints, GoalEndState goalEndState) {
PathPlannerPath path = new PathPlannerPath(globalConstraints, goalEndState);
path.allPoints.addAll(pathPoints);

path.precalcValues();

return path;
}

/** Generate path points for a path. This is used internally and should not be used directly. */
public static List<PathPoint> createPath(
private static List<PathPoint> createPath(
List<Translation2d> bezierPoints,
List<RotationTarget> holonomicRotations,
List<ConstraintsZone> constraintZones) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import java.util.ArrayList;
import java.util.List;

/** Trajectory created from a pathplanner path */
public class PathPlannerTrajectory {
private final List<State> states;

Expand Down Expand Up @@ -222,25 +223,41 @@ public State getEndState() {
return getState(getStates().size() - 1);
}

/** A state along the trajectory */
public static class State {
/** The time at this state in seconds */
public double timeSeconds = 0;

/** The velocity at this state in m/s */
public double velocityMps = 0;
/** The acceleration at this state in m/s^2 */
public double accelerationMpsSq = 0;

/** The time at this state in seconds */
public double headingAngularVelocityRps = 0;

/** The position at this state in meters */
public Translation2d positionMeters = new Translation2d();
/** The heading (direction of travel) at this state */
public Rotation2d heading = new Rotation2d();
/** The target holonomic rotation at this state */
public Rotation2d targetHolonomicRotation = new Rotation2d();

/** The curvature at this state in rad/m */
public double curvatureRadPerMeter = 0;

/** The constraints to apply at this state */
public PathConstraints constraints;

// Values only used during generation
private double deltaPos = 0;

/**
* Interpolate between this state and the given state
*
* @param endVal State to interpolate with
* @param t Interpolation factor (0.0-1.0)
* @return Interpolated state
*/
public State interpolate(State endVal, double t) {
State lerpedState = new State();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,27 +4,52 @@
import edu.wpi.first.math.geometry.Translation2d;
import java.util.Objects;

/** A point along a pathplanner path */
public class PathPoint {
/** The position of this point */
public final Translation2d position;

/** The distance of this point along the path, in meters */
public double distanceAlongPath = 0.0;
/** The curve radius at this point */
public double curveRadius = 0.0;
/** The max velocity at this point */
public double maxV = Double.POSITIVE_INFINITY;
/** The target rotation at this point */
public Rotation2d holonomicRotation = null;
/** The constraints applied to this point */
public PathConstraints constraints = null;

/**
* Create a path point
*
* @param position Position of the point
* @param holonomicRotation Rotation target at this point
* @param constraints The constraints at this point
*/
public PathPoint(
Translation2d position, Rotation2d holonomicRotation, PathConstraints constraints) {
this.position = position;
this.holonomicRotation = holonomicRotation;
this.constraints = constraints;
}

/**
* Create a path point
*
* @param position Position of the point
* @param holonomicRotation Rotation target at this point
*/
public PathPoint(Translation2d position, Rotation2d holonomicRotation) {
this.position = position;
this.holonomicRotation = holonomicRotation;
}

/**
* Create a path point
*
* @param position Position of the point
*/
public PathPoint(Translation2d position) {
this.position = position;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,9 @@
import java.util.List;
import java.util.Optional;

/** A bezier curve segment */
public class PathSegment {
/** The resolution used during path generation */
public static final double RESOLUTION = 0.05;

private final List<PathPoint> segmentPoints;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import java.util.Objects;
import org.json.simple.JSONObject;

/** A target holonomic rotation at a position along a path */
public class RotationTarget {
private final double waypointRelativePosition;
private final Rotation2d target;
Expand Down
Loading

0 comments on commit c3c3c0f

Please sign in to comment.