Package org.team1126.lib.math
Class PAPFController.PointObstacle
java.lang.Object
org.team1126.lib.math.PAPFController.Obstacle
org.team1126.lib.math.PAPFController.PointObstacle
- Enclosing class:
PAPFController
A simple point obstacle. Applies a force from the specified field location.
-
Constructor Summary
ConstructorsConstructorDescriptionPointObstacle(edu.wpi.first.math.geometry.Translation2d location, double strength, double range) Creates a point obstacle.PointObstacle(edu.wpi.first.math.geometry.Translation2d location, double strength, double range, PAPFController.ForceHeuristic heuristic) Creates a point obstacle. -
Method Summary
Modifier and TypeMethodDescriptionvoidapplyForce(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.Methods inherited from class org.team1126.lib.math.PAPFController.Obstacle
getForceMagnitude
-
Constructor Details
-
PointObstacle
public PointObstacle(edu.wpi.first.math.geometry.Translation2d location, double strength, double range) Creates a point obstacle.- Parameters:
location- The point's location on the field.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.
-
PointObstacle
public PointObstacle(edu.wpi.first.math.geometry.Translation2d location, double strength, double range, PAPFController.ForceHeuristic heuristic) Creates a point obstacle.- Parameters:
location- The point's location on the field.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 void applyForce(double x, double y, org.team1126.lib.math.PAPFController.NetForce netForce) Description copied from class:PAPFController.ObstacleApplies the force generated by the obstacle to the provided accumulator, based on the robot's current position and goal.- Specified by:
applyForcein classPAPFController.Obstacle- 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.
-