-
Notifications
You must be signed in to change notification settings - Fork 130
Cpp Example: Follow a Single Path
Michael Jansen edited this page Oct 10, 2023
·
4 revisions
The easiest way to create a command to follow a single path is by using AutoBuilder. You must have previously configured AutoBuilder in order to use this option.
See Cpp Example: Build an Auto
#include <pathplanner/lib/path/PathPlannerPath.h>
#include <pathplanner/lib/auto/AutoBuilder.h>
using namespace pathplanner;
frc2::CommandPtr RobotContainer::getAutonomousCommand(){
// Load the path you want to follow using its name in the GUI
auto path = PathPlannerPath::fromPathFile("Example Path");
// Create a path following command using AutoBuilder. This will also trigger event markers.
return AutoBuilder::followPathWithEvents(path);
}
#include <pathplanner/lib/commands/FollowPathHolonomic.h>
using namespace pathplanner;
// Assuming this is a method in your drive subsystem
frc2::CommandPtr DriveSubsystem::followPathCommand(std::string pathName){
auto path = PathPlannerPath::fromPathFile(pathName);
// You must wrap the path following command in a FollowPathWithEvents command in order for event markers to work
return FollowPathWithEvents(
FollowPathHolonomic(
path,
[this](){ return getPose(); }, // Robot pose supplier
[this](){ return getRobotRelativeSpeeds(); }, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
[this](frc::ChassisSpeeds speeds){ driveRobotRelative(speeds); }, // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds
HolonomicPathFollowerConfig( // HolonomicPathFollowerConfig, this should likely live in your Constants class
PIDConstants(5.0, 0.0, 0.0), // Translation PID constants
PIDConstants(5.0, 0.0, 0.0), // Rotation PID constants
4.5_mps, // Max module speed, in m/s
0.4_m, // Drive base radius in meters. Distance from robot center to furthest module.
ReplanningConfig() // Default path replanning config. See the API for the options here
),
{ this } // Reference to this subsystem to set requirements
).ToPtr().Unwrap(),
path, // FollowPathWithEvents also requires the path
[this](){ return getPose(); } // FollowPathWithEvents also requires the robot pose supplier
).ToPtr();
}
#include <pathplanner/lib/commands/FollowPathRamsete.h>
using namespace pathplanner;
// Assuming this is a method in your drive subsystem
frc2::CommandPtr DriveSubsystem::followPathCommand(std::string pathName){
auto path = PathPlannerPath::fromPathFile(pathName);
// You must wrap the path following command in a FollowPathWithEvents command in order for event markers to work
return FollowPathWithEvents(
FollowPathRamsete(
path,
[this](){ return getPose(); }, // Robot pose supplier
[this](){ return getRobotRelativeSpeeds(); }, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
[this](frc::ChassisSpeeds speeds){ driveRobotRelative(speeds); }, // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds
ReplanningConfig(), // Default path replanning config. See the API for the options here
{ this } // Reference to this subsystem to set requirements
).ToPtr().Unwrap(),
path, // FollowPathWithEvents also requires the path
[this](){ return getPose(); } // FollowPathWithEvents also requires the robot pose supplier
).ToPtr();
}
#include <pathplanner/lib/commands/FollowPathLTV.h>
using namespace pathplanner;
// Assuming this is a method in your drive subsystem
frc2::CommandPtr DriveSubsystem::followPathCommand(std::string pathName){
auto path = PathPlannerPath::fromPathFile(pathName);
// You must wrap the path following command in a FollowPathWithEvents command in order for event markers to work
return FollowPathWithEvents(
FollowPathLTV(
path,
[this](){ return getPose(); }, // Robot pose supplier
[this](){ return getRobotRelativeSpeeds(); }, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
[this](frc::ChassisSpeeds speeds){ driveRobotRelative(speeds); }, // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds
0.02_s, // Robot control loop period in seconds. Default is 0.02
ReplanningConfig(), // Default path replanning config. See the API for the options here
{ this } // Reference to this subsystem to set requirements
).ToPtr().Unwrap(),
path, // FollowPathWithEvents also requires the path
[this](){ return getPose(); } // FollowPathWithEvents also requires the robot pose supplier
).ToPtr();
}
- Controls & Shortcuts
- Editing Paths & Autos
- Navigation Menu
- Settings
- Project Browser
- Telemetry Page
- Navigation Grid Editor
- Register Named Commands
- Build an Auto
- Follow a Single Path
- Create a Path On-the-fly
- Path Groups
- Automatic Pathfinding
Advanced Usage
- Register Named Commands
- Build an Auto
- Follow a Single Path
- Create a Path On-the-fly
- Path Groups
- Automatic Pathfinding
Advanced Usage
- Register Named Commands
- Build an Auto
- Follow a Single Path
- Create a Path On-the-fly
- Path Groups
- Automatic Pathfinding