-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
move and auto align at the same time
- Loading branch information
1 parent
8765be3
commit 34a6146
Showing
4 changed files
with
129 additions
and
7 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
116 changes: 116 additions & 0 deletions
116
src/main/java/frc/robot/commands/alignmentDriveCommand.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,116 @@ | ||
package frc.robot.commands; | ||
|
||
import com.pathplanner.lib.commands.PathfindHolonomic; | ||
import edu.wpi.first.math.MathUtil; | ||
import edu.wpi.first.math.geometry.Pose2d; | ||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.math.geometry.Transform2d; | ||
import edu.wpi.first.math.geometry.Translation2d; | ||
import edu.wpi.first.math.kinematics.ChassisSpeeds; | ||
import edu.wpi.first.wpilibj.DriverStation; | ||
import edu.wpi.first.wpilibj2.command.Command; | ||
import frc.robot.Constants.DriveConstants; | ||
import frc.robot.subsystems.drive.DriveSubsystem; | ||
import lib.utils.AllianceFlipUtil; | ||
|
||
import java.util.function.DoubleSupplier; | ||
import java.util.function.Supplier; | ||
|
||
import static frc.robot.commands.DriveCommands.DEADBAND; | ||
|
||
|
||
public class alignmentDriveCommand extends Command { | ||
private final DriveSubsystem driveSubsystem; | ||
private final Supplier<Pose2d> pointSupplier; | ||
private Command alignmentCommand; | ||
|
||
private final DoubleSupplier xSupplier; | ||
private final DoubleSupplier ySupplier; | ||
private final DoubleSupplier thetaSupplier; | ||
|
||
public alignmentDriveCommand(DriveSubsystem driveSubsystem, | ||
DoubleSupplier xSupplier, | ||
DoubleSupplier ySupplier, | ||
DoubleSupplier thetaSupplier, | ||
Supplier<Pose2d> point) { | ||
this.driveSubsystem = driveSubsystem; | ||
this.pointSupplier = point; | ||
|
||
|
||
|
||
this.xSupplier = xSupplier; | ||
this.ySupplier =ySupplier; | ||
this.thetaSupplier = thetaSupplier; | ||
|
||
// each subsystem used by the command must be passed into the | ||
// addRequirements() method (which takes a vararg of Subsystem) | ||
addRequirements(this.driveSubsystem); | ||
} | ||
|
||
@Override | ||
public void initialize() { | ||
Pose2d point = AllianceFlipUtil.apply(pointSupplier.get()); | ||
alignmentCommand = new PathfindHolonomic( | ||
point, | ||
DriveConstants.DEFAULT_CONSTRAINTS, | ||
0.0, | ||
driveSubsystem::getVisionPose, | ||
driveSubsystem::getRobotRelativeSpeeds, | ||
driveSubsystem::runVelocity, | ||
DriveConstants.HOLONOMIC_CONFIG, | ||
0.0, | ||
driveSubsystem | ||
); | ||
} | ||
|
||
@Override | ||
public void execute() { | ||
double xInput = DriveCommands.setSensitivity(xSupplier.getAsDouble(), 0.25); | ||
double yInput = DriveCommands.setSensitivity(ySupplier.getAsDouble(), 0.25); | ||
double omegaInput = DriveCommands.setSensitivity(thetaSupplier.getAsDouble(), 0.0) * 0.85; | ||
|
||
// if we have actual driver input | ||
if (xInput > DEADBAND | ||
|| yInput > DEADBAND | ||
|| omegaInput > DEADBAND) { | ||
// Apply deadband | ||
double linearMagnitude = | ||
MathUtil.applyDeadband( | ||
Math.hypot(xInput, yInput), DEADBAND); | ||
Rotation2d linearDirection = | ||
new Rotation2d(xInput, yInput); | ||
double omega = MathUtil.applyDeadband(omegaInput, DEADBAND); | ||
|
||
// Calcaulate new linear velocity | ||
Translation2d linearVelocity = | ||
new Pose2d(new Translation2d(), linearDirection) | ||
.transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())) | ||
.getTranslation(); | ||
|
||
Rotation2d heading; | ||
|
||
// if red change heading goal | ||
if (DriverStation.getAlliance().isPresent() | ||
&& DriverStation.getAlliance().get() == DriverStation.Alliance.Red) { | ||
heading = driveSubsystem.getRotation().plus(Rotation2d.fromDegrees(180)); | ||
} else { | ||
heading = driveSubsystem.getRotation(); | ||
} | ||
|
||
// Convert to field relative speeds & send command | ||
driveSubsystem.runVelocity( | ||
ChassisSpeeds.fromFieldRelativeSpeeds( | ||
linearVelocity.getX() * driveSubsystem.getMaxLinearSpeedMetersPerSec(), | ||
linearVelocity.getY() * driveSubsystem.getMaxLinearSpeedMetersPerSec(), | ||
omega * driveSubsystem.getMaxAngularSpeedRadPerSec(), | ||
heading)); | ||
} else { | ||
alignmentCommand.execute(); | ||
} | ||
} | ||
|
||
@Override | ||
public boolean isFinished() { | ||
return false; | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters