Package org.team1126.lib.math
Class PAPFController.Obstacle
java.lang.Object
org.team1126.lib.math.PAPFController.Obstacle
- Direct Known Subclasses:
PAPFController.CircleObstacle,PAPFController.LateralObstacle,PAPFController.LineObstacle,PAPFController.LongitudinalObstacle,PAPFController.PointObstacle
- Enclosing class:
PAPFController
A generic obstacle.
-
Constructor Summary
ConstructorsConstructorDescriptionObstacle(double strength, double range) Creates an obstacle.Obstacle(double strength, double range, PAPFController.ForceHeuristic heuristic) Creates an obstacle. -
Method Summary
Modifier and TypeMethodDescriptionabstract voidapplyForce(double x, double y, org.team1126.lib.math.PAPFController.NetForce netForce) Applies the force generated by the obstacle to the provided accumulator, based on the robot's current position and goal.protected final doublegetForceMagnitude(double dist) Converts a distance from the obstacle to the strength of the force.
-
Constructor Details
-
Obstacle
public Obstacle(double strength, double range) Creates an obstacle.- Parameters:
strength- The strength of the obstacle's force. Positive values represent a repulsive potential (pushes away), negative values represent an attractive potential (pulls towards).range- The range of the obstacle's potential, in meters.
-
Obstacle
Creates an obstacle.- Parameters:
strength- The strength of the obstacle's force. Positive values represent a repulsive potential (pushes away), negative values represent an attractive potential (pulls towards).range- The range of the obstacle's potential, in meters.heuristic- A heuristic for transforming the obstacle's force profile.
-
-
Method Details
-
applyForce
public abstract void applyForce(double x, double y, org.team1126.lib.math.PAPFController.NetForce netForce) Applies the force generated by the obstacle to the provided accumulator, based on the robot's current position and goal.- Parameters:
x- The robot's current X position on the field.y- The robot's current Y position on the field.netForce- The force accumulator to apply the force to.
-
getForceMagnitude
protected final double getForceMagnitude(double dist) Converts a distance from the obstacle to the strength of the force.- Parameters:
dist- The distance from the obstacle.
-