Skip to content

Commit

Permalink
[#29] - added base code for pathfinding to a point and auton
Browse files Browse the repository at this point in the history
  • Loading branch information
HeeistHo committed Mar 9, 2024
1 parent 598b0eb commit abc2e33
Show file tree
Hide file tree
Showing 6 changed files with 215 additions and 7 deletions.
52 changes: 52 additions & 0 deletions src/main/deploy/pathplanner/paths/New Path.path
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
{
"version": 1.0,
"waypoints": [
{
"anchor": {
"x": 9.647717313452645,
"y": 4.335765788648695
},
"prevControl": null,
"nextControl": {
"x": 10.647717313452642,
"y": 4.335765788648695
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 4.0,
"y": 6.0
},
"prevControl": {
"x": 3.0,
"y": 6.0
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0
},
"goalEndState": {
"velocity": 0,
"rotation": 0,
"rotateFast": false
},
"reversed": false,
"folder": null,
"previewStartingState": {
"rotation": 0,
"velocity": 0
},
"useDefaultConstraints": true
}
8 changes: 5 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -150,9 +150,6 @@ public static class AutonomousConstants {
public static final PathConstraints PATH_CONSTRAINTS = new PathConstraints(2.0, 1, 1.0, 0.5); // TODO get
// constants

// For Pathfinding
// TODO get real poses to pathfind to
public static final Pose2d TARGET_POSE = new Pose2d(new Translation2d(0, 0), new Rotation2d(0d));

}

Expand Down Expand Up @@ -338,6 +335,11 @@ public class Pipelines { // TODO get real
}
}

public class PathFindingConstants {
public static final Pose2d TEST_POSE = new Pose2d(9, 4, new Rotation2d(90));
public static final Translation2d RED_ORIGIN = new Translation2d(16.4592, 0);
}

public class CollisionConstants {
public static final double TIP_DEADZONE = 2d;

Expand Down
14 changes: 11 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
import com.ctre.phoenix6.mechanisms.swerve.SwerveRequest;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import com.pathplanner.lib.path.PathConstraints;
import com.pathplanner.lib.path.PathPlannerPath;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.DriverStation;
Expand All @@ -19,6 +21,7 @@
import frc.robot.Constants.ControllerConstants;
import frc.robot.Constants.DrivetrainConstants;
import frc.robot.Constants.IndexerConstants;
import frc.robot.Constants.PathFindingConstants;
import frc.robot.Constants.IndexerConstants.PieceState;
import frc.robot.Constants.LEDsConstants.LED_STATES;
import frc.robot.Constants.TunerConstants;
Expand All @@ -29,6 +32,8 @@
import frc.robot.command.CollisionDetection;
import frc.robot.command.Index;
import frc.robot.command.MoveToPose;
import frc.robot.command.PathFindToAuton;
import frc.robot.command.PathToPose;
import frc.robot.command.PointAtPoint;
import frc.robot.command.ManualClimb;
import frc.robot.command.PointAtTag;
Expand Down Expand Up @@ -144,7 +149,7 @@ protected void initializeNamedCommands() {
new SmartCollect(() -> .5d, () -> .6d, collector, indexer, pivot, flywheel)
.deadlineWith(leds.enableState(LED_STATES.COLLECTING).withTimeout(1)));
NamedCommands.registerCommand("Index-Up", new Index(() -> IndexerConstants.INDEXER_DEFAULT_POWER, indexer));
NamedCommands.registerCommand("PathFind", new MoveToPose(AutonomousConstants.TARGET_POSE, drivetrain));
NamedCommands.registerCommand("PathFind", new PathToPose(PathFindingConstants.TEST_POSE, drivetrain, driver));
NamedCommands.registerCommand("Collect-And-Go", new CollectAndGo(collector, flywheel, indexer));

// make sure named commands are initialized before autobuilder!
Expand Down Expand Up @@ -172,9 +177,12 @@ protected void configureButtonBindings() {
.onTrue(drivetrain.runOnce(drivetrain::seedFieldRelative));

// makes the robot chase pieces
// new Trigger(driver::getRightBumper)
// .whileTrue(new ChasePieces(drivetrain, collector, indexer, pivot, flywheel, limelights)
// .deadlineWith(leds.enableState(LED_STATES.CHASING)));

new Trigger(driver::getRightBumper)
.whileTrue(new ChasePieces(drivetrain, collector, indexer, pivot, flywheel, limelights)
.deadlineWith(leds.enableState(LED_STATES.CHASING)));
.whileTrue(new PathFindToAuton(PathPlannerPath.fromPathFile("C2-C1"), drivetrain, coPilot));

// parks the robot
// new Trigger(driver::getXButton).whileTrue(new InstantCommand(() ->
Expand Down
74 changes: 74 additions & 0 deletions src/main/java/frc/robot/command/PathFindToAuton.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.command;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.path.PathConstraints;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.path.PathPoint;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.AutonomousConstants;
import frc.robot.Constants.PathFindingConstants;
import frc.robot.subsystems.Swerve;
import frc.thunder.filter.XboxControllerFilter;

public class PathFindToAuton extends Command {

private Swerve drivetrain;
private XboxControllerFilter controller; // Driver Controller
private AutoBuilder autoBuilder;
private Command pathFindCommand;
private PathPlannerPath autonPath;

/*
* Pathfinds to a specific pose given
* @param pathfindingPose The pose to pathfind to
* @param drivetrain The drivetrain subsystem
* @param controller The driver controller
*/
public PathFindToAuton(PathPlannerPath autonPath, Swerve drivetrain, XboxControllerFilter controller) {
this.drivetrain = drivetrain;
this.controller = controller;
this.autonPath = autonPath;
autoBuilder = new AutoBuilder();

addRequirements(drivetrain);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
pathFindCommand = autoBuilder.pathfindThenFollowPath(
autonPath, AutonomousConstants.PATH_CONSTRAINTS);
pathFindCommand.schedule();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {

}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
pathFindCommand.cancel();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
if (pathFindCommand.isFinished()) {
return true;
}
return false;
}
}
72 changes: 72 additions & 0 deletions src/main/java/frc/robot/command/PathToPose.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.command;

import com.pathplanner.lib.auto.AutoBuilder;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.AutonomousConstants;
import frc.robot.subsystems.Swerve;
import frc.thunder.filter.XboxControllerFilter;

public class PathToPose extends Command {

private Swerve drivetrain;
private XboxControllerFilter controller; // Driver Controller
private Pose2d pathfindingPose;
private AutoBuilder autoBuilder;
Command pathFindCommand;

/*
* Pathfinds to a specific pose given
* @param pathfindingPose The pose to pathfind to
* @param drivetrain The drivetrain subsystem
* @param controller The driver controller
*/
public PathToPose(Pose2d pathfindingPose, Swerve drivetrain, XboxControllerFilter controller) {
this.drivetrain = drivetrain;
this.controller = controller;
this.pathfindingPose = pathfindingPose;

autoBuilder = new AutoBuilder();

addRequirements(drivetrain);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
pathFindCommand = autoBuilder.pathfindToPose(
pathfindingPose, AutonomousConstants.PATH_CONSTRAINTS
);
pathFindCommand.schedule();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if (controller.getYButton()) {
end(true);
}
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
if (interrupted) {
pathFindCommand.cancel();
}
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
if (pathFindCommand.isFinished()) {
return true;
}
return false;
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/thunder
Submodule thunder updated 1 files
+4 −0 util/Pose4d.java

0 comments on commit abc2e33

Please sign in to comment.