#include <PathPlannerAuto.h>
|
static std::string | currentPathName = "" |
|
A command that loads and runs an autonomous routine built using PathPlanner.
◆ PathPlannerAuto() [1/3]
PathPlannerAuto::PathPlannerAuto |
( |
std::string |
autoName | ) |
|
Constructs a new PathPlannerAuto command.
- Parameters
-
autoName | the name of the autonomous routine to load and run |
◆ PathPlannerAuto() [2/3]
PathPlannerAuto::PathPlannerAuto |
( |
std::string |
autoName, |
|
|
bool |
mirror |
|
) |
| |
Constructs a new PathPlannerAuto command.
- Parameters
-
autoName | the name of the autonomous routine to load and run |
mirror | Mirror all paths to the other side of the current alliance. For example, if a path is on the right of the blue alliance side of the field, it will be mirrored to the left of the blue alliance side of the field. |
◆ PathPlannerAuto() [3/3]
PathPlannerAuto::PathPlannerAuto |
( |
frc2::CommandPtr && |
autoCommand, |
|
|
frc::Pose2d |
startingPose = frc::Pose2d() |
|
) |
| |
Create a PathPlannerAuto from a custom command
- Parameters
-
autoCommand | The command this auto should run |
startingPose | The starting pose of the auto. Only used for the getStartingPose method |
◆ activePath()
frc2::Trigger pathplanner::PathPlannerAuto::activePath |
( |
std::string |
pathName | ) |
|
|
inline |
Create a trigger that is high when a certain path is being followed
- Parameters
-
pathName | The name of the path to check for |
- Returns
- activePath trigger
◆ condition()
frc2::Trigger pathplanner::PathPlannerAuto::condition |
( |
std::function< bool()> |
condition | ) |
|
|
inline |
Create a trigger with a custom condition. This will be polled by this auto's event loop so that its condition is only polled when this auto is running.
- Parameters
-
condition | The condition represented by this trigger |
- Returns
- Custom condition trigger
◆ event()
EventTrigger pathplanner::PathPlannerAuto::event |
( |
std::string |
eventName | ) |
|
|
inline |
Create an EventTrigger that will be polled by this auto instead of globally across all path following commands
- Parameters
-
eventName | The event name that controls this trigger |
- Returns
- EventTrigger for this auto
◆ getPathGroupFromAutoFile()
std::vector< std::shared_ptr< PathPlannerPath > > PathPlannerAuto::getPathGroupFromAutoFile |
( |
std::string |
autoName | ) |
|
|
static |
Get a vector of every path in the given auto (depth first)
- Parameters
-
autoName | Name of the auto to get the path group from |
- Returns
- Vector of paths in the auto
◆ getStartingPose()
constexpr frc::Pose2d pathplanner::PathPlannerAuto::getStartingPose |
( |
| ) |
const |
|
inlineconstexpr |
Get the starting pose of this auto, relative to a blue alliance origin. If there are no paths in this auto, the starting pose will be (0, 0, 0).
- Returns
- The blue alliance starting pose
◆ inFieldArea()
frc2::Trigger PathPlannerAuto::inFieldArea |
( |
frc::Translation2d |
boundingBoxMin, |
|
|
frc::Translation2d |
boundingBoxMax |
|
) |
| |
Create a trigger that will be high when the robot is within a given area on the field. These positions will not be automatically flipped
- Parameters
-
boundingBoxMin | The minimum position of the bounding box for the target field area. The X & Y coordinates of this position should be less than the max position. |
boundingBoxMax | The maximum position of the bounding box for the target field area. The X & Y coordinates of this position should be greater than the min position. |
- Returns
- inFieldArea trigger
◆ inFieldAreaAutoFlipped()
frc2::Trigger PathPlannerAuto::inFieldAreaAutoFlipped |
( |
frc::Translation2d |
blueBoundingBoxMin, |
|
|
frc::Translation2d |
blueBoundingBoxMax |
|
) |
| |
Create a trigger that will be high when the robot is within a given area on the field. These positions will be automatically flipped
- Parameters
-
blueBoundingBoxMin | The minimum position of the bounding box for the target field area if on the blue alliance. The X & Y coordinates of this position should be less than the max position. |
blueBoundingBoxMax | The maximum position of the bounding box for the target field area if on the blue alliance. The X & Y coordinates of this position should be greater than the min position. |
- Returns
- inFieldAreaAutoFlipped trigger
◆ isRunning()
frc2::Trigger pathplanner::PathPlannerAuto::isRunning |
( |
| ) |
|
|
inline |
Create a trigger that is high when this auto is running, and low when it is not running
- Returns
- isRunning trigger
◆ nearFieldPosition()
frc2::Trigger pathplanner::PathPlannerAuto::nearFieldPosition |
( |
frc::Translation2d |
fieldPosition, |
|
|
units::meter_t |
tolerance |
|
) |
| |
|
inline |
Create a trigger that is high when near a given field position. This field position is not automatically flipped
- Parameters
-
fieldPosition | The target field position |
tolerance | The position tolerance, in meters. The trigger will be high when within this distance from the target position |
- Returns
- nearFieldPosition trigger
◆ nearFieldPositionAutoFlipped()
frc2::Trigger PathPlannerAuto::nearFieldPositionAutoFlipped |
( |
frc::Translation2d |
blueFieldPosition, |
|
|
units::meter_t |
tolerance |
|
) |
| |
Create a trigger that is high when near a given field position. This field position will be automatically flipped
- Parameters
-
blueFieldPosition | The target field position if on the blue alliance |
tolerance | The position tolerance, in meters. The trigger will be high when within this distance from the target position |
- Returns
- nearFieldPositionAutoFlipped trigger
◆ pointTowardsZone()
Create a PointTowardsZoneTrigger that will be polled by this auto instead of globally across all path following commands
- Parameters
-
zoneName | The point towards zone name that controls this trigger |
- Returns
- PointTowardsZoneTrigger for this auto
◆ timeElapsed()
frc2::Trigger pathplanner::PathPlannerAuto::timeElapsed |
( |
units::second_t |
time | ) |
|
|
inline |
Trigger that is high when the given time has elapsed
- Parameters
-
time | The amount of time this auto should run before the trigger is activated |
- Returns
- timeElapsed trigger
◆ timeRange()
frc2::Trigger pathplanner::PathPlannerAuto::timeRange |
( |
units::second_t |
startTime, |
|
|
units::second_t |
endTime |
|
) |
| |
|
inline |
Trigger that is high when within a range of time since the start of this auto
- Parameters
-
startTime | The starting time of the range |
endTime | The ending time of the range |
- Returns
- timeRange trigger
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/commands/PathPlannerAuto.h
- src/main/native/cpp/pathplanner/lib/commands/PathPlannerAuto.cpp