Skip to content

Commit

Permalink
move and auto align at the same time
Browse files Browse the repository at this point in the history
  • Loading branch information
GearBoxFox committed Mar 12, 2024
1 parent 8765be3 commit 34a6146
Show file tree
Hide file tree
Showing 4 changed files with 129 additions and 7 deletions.
12 changes: 7 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,7 @@
import edu.wpi.first.wpilibj2.command.button.Trigger;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.Constants.DriveConstants;
import frc.robot.commands.DriveCommands;
import frc.robot.commands.FeedForwardCharacterization;
import frc.robot.commands.IntakeControlCommand;
import frc.robot.commands.ShooterAutoCommand;
import frc.robot.commands.*;
import frc.robot.subsystems.arm.*;
import frc.robot.subsystems.climber.ClimberIO;
import frc.robot.subsystems.climber.ClimberIOKraken;
Expand Down Expand Up @@ -224,8 +221,13 @@ private void configureButtonBindings() {
() -> AllianceFlipUtil.apply(FieldConstants.CENTER_SPEAKER)
)));

ampLineupTrigger.whileTrue(new ScheduleCommand(m_driveSubsystem.pathfollowFactory(FieldConstants.AMP_LINEUP))
ampLineupTrigger.whileTrue(new alignmentDriveCommand(m_driveSubsystem,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> -controller.getRightX(),
() -> FieldConstants.AMP_LINEUP)
.andThen(m_armSubsystem.setDesiredStateFactory(ArmSubsystem.ArmState.AMP)));

ampDepositeTrigger.whileTrue(Commands.runEnd(() -> m_shooter.setKickerPower(-0.5),
() -> m_shooter.setKickerPower(0.0),
m_shooter)
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/DriveCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
import java.util.function.Supplier;

public class DriveCommands {
private static final double DEADBAND = 0.1;
public static final double DEADBAND = 0.1;

private DriveCommands() {}

Expand Down
116 changes: 116 additions & 0 deletions src/main/java/frc/robot/commands/alignmentDriveCommand.java
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;
}
}
6 changes: 5 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -395,4 +395,8 @@ public Command runSysidQuasistatic(SysIdRoutine.Direction direction) {
public Command runSysidDynamic(SysIdRoutine.Direction direction) {
return m_sysId.dynamic(direction);
}
}

public ChassisSpeeds getRobotRelativeSpeeds() {
return kinematics.toChassisSpeeds(getModuleStates());
}
}

0 comments on commit 34a6146

Please sign in to comment.