◆ PointTowardsZone() [1/2]
pathplanner::PointTowardsZone::PointTowardsZone |
( |
std::string |
name, |
|
|
frc::Translation2d |
targetPosition, |
|
|
frc::Rotation2d |
rotationOffset, |
|
|
double |
minWaypointRelativePos, |
|
|
double |
maxWaypointRelativePos |
|
) |
| |
|
inline |
Create a new point towards zone
- Parameters
-
name | The name of this zone. Used for point towards zone triggers |
targetPosition | The target field position in meters |
rotationOffset | A rotation offset to add on top of the angle to the target position. For example, if you want the robot to point away from the target position, use a rotation offset of 180 degrees |
minWaypointRelativePos | Starting position of the zone |
maxWaypointRelativePos | End position of the zone |
◆ PointTowardsZone() [2/2]
pathplanner::PointTowardsZone::PointTowardsZone |
( |
std::string |
name, |
|
|
frc::Translation2d |
targetPosition, |
|
|
double |
minWaypointRelativePos, |
|
|
double |
maxWaypointRelativePos |
|
) |
| |
|
inline |
Create a new point towards zone
- Parameters
-
name | The name of this zone. Used for point towards zone triggers |
targetPosition | The target field position in meters |
minWaypointRelativePos | Starting position of the zone |
maxWaypointRelativePos | End position of the zone |
◆ fromJson()
static PointTowardsZone pathplanner::PointTowardsZone::fromJson |
( |
const wpi::json & |
json | ) |
|
|
inlinestatic |
Create a point towards zone from json
- Parameters
-
json | A json reference representing a point towards zone |
- Returns
- The point towards zone defined by the given json object
◆ getMaxWaypointRelativePos()
constexpr double pathplanner::PointTowardsZone::getMaxWaypointRelativePos |
( |
| ) |
const |
|
inlineconstexpr |
Get the end position of the zone
- Returns
- Waypoint relative end position
◆ getMinWaypointRelativePos()
constexpr double pathplanner::PointTowardsZone::getMinWaypointRelativePos |
( |
| ) |
const |
|
inlineconstexpr |
Get the starting position of the zone
- Returns
- Waypoint relative starting position
◆ getRotationOffset()
constexpr frc::Rotation2d & pathplanner::PointTowardsZone::getRotationOffset |
( |
| ) |
|
|
inlineconstexpr |
Get the rotation offset
- Returns
- Rotation offset
◆ getTargetPosition()
constexpr frc::Translation2d & pathplanner::PointTowardsZone::getTargetPosition |
( |
| ) |
|
|
inlineconstexpr |
Get the target field position to point at
- Returns
- Target field position in meters
The documentation for this class was generated from the following file: