Package org.team1126.lib.math
Interface PAPFController.GoalHeuristic
- Enclosing class:
PAPFController
- Functional Interface:
- This is a functional interface and can therefore be used as the assignment target for a lambda expression or method reference.
Represents a heuristic for calculating the strength of
the attractive force generated by the goal location.
-
Field Summary
FieldsModifier and TypeFieldDescriptionstatic final PAPFController.GoalHeuristicThe default heuristic. -
Method Summary
Modifier and TypeMethodDescriptiondoubleapply(double d) Applies the heuristic to a specified distance from the goal location, returning an arbitrary strength value.
-
Field Details
-
DEFAULT
The default heuristic. Returns a static base strength of1.0in addition to an increasing strength of2.0 / distanceto have greater influence on the robot as it approaches the goal location.
-
-
Method Details
-
apply
double apply(double d) Applies the heuristic to a specified distance from the goal location, returning an arbitrary strength value.- Parameters:
d- The robot's current distance from the goal location, in meters. This value will always be positive and non-zero.- Returns:
- A strength value, relative to the strength specified for obstacles.
-