ChoreoLib
Loading...
Searching...
No Matches
choreolib::Choreo Class Reference

#include <Choreo.h>

Static Public Member Functions

static ChoreoTrajectory GetTrajectory (std::string_view trajName)
 
static std::vector< ChoreoTrajectoryGetTrajectoryGroup (std::string_view trajName)
 
static frc2::CommandPtr ChoreoSwerveCommandFactory (ChoreoTrajectory trajectory, std::function< frc::Pose2d()> poseSupplier, frc::PIDController xController, frc::PIDController yController, frc::PIDController rotationController, std::function< void(frc::ChassisSpeeds)> outputChassisSpeeds, std::function< bool(void)> mirrorTrajectory, frc2::Requirements requirements={})
 
static frc2::CommandPtr ChoreoSwerveCommandFactory (ChoreoTrajectory trajectory, std::function< frc::Pose2d()> poseSupplier, ChoreoControllerFunction controller, std::function< void(frc::ChassisSpeeds)> outputChassisSpeeds, std::function< bool(void)> mirrorTrajectory, frc2::Requirements requirements={})
 
static ChoreoControllerFunction ChoreoSwerveController (frc::PIDController xController, frc::PIDController yController, frc::PIDController rotationController)
 

Detailed Description

A class that handles loading choreo trajectories and creating command factories for following trajectories

Member Function Documentation

◆ ChoreoSwerveCommandFactory() [1/2]

frc2::CommandPtr Choreo::ChoreoSwerveCommandFactory ( ChoreoTrajectory trajectory,
std::function< frc::Pose2d()> poseSupplier,
ChoreoControllerFunction controller,
std::function< void(frc::ChassisSpeeds)> outputChassisSpeeds,
std::function< bool(void)> mirrorTrajectory,
frc2::Requirements requirements = {} )
static

Creates a CommandPtr that commands your drivebase to follow a Choreo trajectory

Parameters
trajectorya ChoreoTrajectory to follow
poseSuppliera function that returns a Pose2d of the robots current position
controllera ChoreoControllerFunction that handles the feedback of the robots position
outputChassisSpeedsa function that consuming the calculated robot relative ChassisSpeeds
mirrorTrajectoryIf this returns true, the path will be mirrored to the opposite side, while keeping the same coordinate system origin. This will be called every loop during the command.
requirementsthe frc2::Requirements of the command
Returns
an frc2::CommandPtr containing the command that will command your drivebase to follow a trajectory

◆ ChoreoSwerveCommandFactory() [2/2]

frc2::CommandPtr Choreo::ChoreoSwerveCommandFactory ( ChoreoTrajectory trajectory,
std::function< frc::Pose2d()> poseSupplier,
frc::PIDController xController,
frc::PIDController yController,
frc::PIDController rotationController,
std::function< void(frc::ChassisSpeeds)> outputChassisSpeeds,
std::function< bool(void)> mirrorTrajectory,
frc2::Requirements requirements = {} )
static

Creates a CommandPtr that commands your drivebase to follow a Choreo trajectory

Parameters
trajectorya ChoreoTrajectory to follow
poseSuppliera function that returns a Pose2d of the robots current position
xControllera PIDController that controls the feedback on the global x position of the robot
yControllera PIDController that controls the feedback on the global y position of the robot
rotationControllera PIDController that controls the feedback on the global heading of the robot
outputChassisSpeedsa function that consuming the calculated robot relative ChassisSpeeds
mirrorTrajectoryIf this returns true, the path will be mirrored to the opposite side, while keeping the same coordinate system origin. This will be called every loop during the command.
requirementsthe frc2::Requirements of the command
Returns
an frc2::CommandPtr containing the command that will command your drivebase to follow a trajectory

◆ ChoreoSwerveController()

ChoreoControllerFunction Choreo::ChoreoSwerveController ( frc::PIDController xController,
frc::PIDController yController,
frc::PIDController rotationController )
static

Creates a ChoreoControllerFunction handles the feedback of the drivebase position

Parameters
xControllera PIDController that controls the feedback on the global x position of the robot
yControllera PIDController that controls the feedback on the global y position of the robot
rotationControllera PIDController that controls the feedback on the global heading of the robot
Returns
a ChoreoControllerFunction that handles the feedback of the drivebase position

◆ GetTrajectory()

ChoreoTrajectory Choreo::GetTrajectory ( std::string_view trajName)
static

Load a trajectory from the deploy directory. ChoreoLib expects .traj files to be placed in src/main/deploy/choreo/[trajName].traj .

Parameters
trajNamethe path name in Choreo, which matches the file name in the deploy directory. Do not include ".traj" here.
Returns
the loaded trajectory, will throw runtime error if the file doesn't exist

◆ GetTrajectoryGroup()

std::vector< ChoreoTrajectory > Choreo::GetTrajectoryGroup ( std::string_view trajName)
static

Loads the split parts of the specified trajectory.

ChoreoLib expects split .traj files to be placed in src/main/deploy/choreo/[trajName].[segmentNumber].traj.

This method determines the number of parts to load by counting the files that match the pattern "trajName.X.traj", where X is a string of digits. Let this count be N. It then attempts to load "trajName.1.traj" through "trajName.N.traj", consecutively counting up.

Parameters
trajNamethe path name in Choreo. Do not include ".traj" here.
Returns
The array of segments, in order.
Exceptions
std::runtime_errorIf any files cannot be loaded.

The documentation for this class was generated from the following files: