Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/driver/DriverXbox.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import frc.robot.rushinator.RushinatorWrist;
import frc.robot.rushinator.commands.SetArmState;
import frc.robot.rushinator.commands.SetWristState;
import frc.robot.vision.commands.LineupCommand;


public class DriverXbox extends XboxGamepad {
Expand Down Expand Up @@ -59,6 +60,7 @@ public void setupTeleopButtons() {

controller.rightBumper().whileTrue(new InstantCommand(() -> RobotContainer.modeFast = false));
controller.rightBumper().whileFalse(new InstantCommand(() -> RobotContainer.modeFast = true));
controller.leftBumper().onTrue(new LineupCommand());

/*Algae Pivot TEsting */
// controller.a().onTrue(AlgaePivotCommands.setAlgaePivotAngle(AlgaeSubsystem.State.kFloorIntake));
Expand Down
32 changes: 27 additions & 5 deletions src/main/java/frc/robot/vision/commands/LineupCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import static edu.wpi.first.units.Units.MetersPerSecondPerSecond;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond;
import static edu.wpi.first.units.Units.RotationsPerSecond;

import java.util.Optional;

Expand All @@ -26,6 +27,7 @@
import edu.wpi.first.wpilibj2.command.Command;

import frc.robot.vision.VisionConfig;
import frc.robot.RobotContainer;
import frc.robot.drivetrain.*;
import frc.robot.vision.PoseEstimatorSubsystem;

Expand Down Expand Up @@ -63,6 +65,7 @@ public class LineupCommand extends Command {


private static Pose2d currentPose;
private static Pose2d targetPose;

public LineupCommand() {
//set tolerances of all PID controllers
Expand All @@ -73,7 +76,7 @@ public LineupCommand() {
thetaController.enableContinuousInput(Units.degreesToRadians(-180), Units.degreesToRadians(180));

currentPose = PoseEstimatorSubsystem.getInstance().getCurrentPose();
Pose2d targetPose = getTargetReefPose(true);
targetPose = getTargetReefPose(true);

xDistanceController.reset(0);
yDistanceController.reset(0);
Expand All @@ -91,15 +94,34 @@ public void initialize() {
public void execute() {
currentPose = PoseEstimatorSubsystem.getInstance().getCurrentPose();
ChassisSpeeds currentSpeeds = CommandSwerveDrivetrain.getInstance().getState().Speeds;
double xPose = currentPose.getTranslation().getX();
double yPose = currentPose.getTranslation().getY();

double Xpos = currentPose.getTranslation().getX();
double Ypos = currentPose.getTranslation().getY();
double Xvel = currentSpeeds.vxMetersPerSecond;
double Yvel = currentSpeeds.vyMetersPerSecond;
double XOutput = 0.15 * TunerConstants.kSpeedAt12Volts.in(MetersPerSecond) * 0.95 * xDistanceController.calculate(Xpos, targetPose.getX());
double YOutput = 0.15 * TunerConstants.kSpeedAt12Volts.in(MetersPerSecond) * 0.95 * xDistanceController.calculate(Ypos, targetPose.getY());
double thetaOutput = 0.15 * RotationsPerSecond.of(0.75).in(RadiansPerSecond) * thetaController.calculate(currentPose.getRotation().getRadians(), targetPose.getRotation().getRadians());

if (DriverStation.getAlliance().get() == Alliance.Blue){
CommandSwerveDrivetrain.getInstance().applyRequest(() ->
RobotContainer.drive.withVelocityX(XOutput)
.withVelocityY(YOutput)
.withRotationalRate(thetaOutput)
).execute();
} else {
CommandSwerveDrivetrain.getInstance().applyRequest(() ->
RobotContainer.drive.withVelocityX(-XOutput)
.withVelocityY(-YOutput)
.withRotationalRate(thetaOutput)
).execute();
}

}


@Override
public boolean isFinished() {
return false;
return xDistanceController.atSetpoint() && yDistanceController.atSetpoint() && thetaController.atSetpoint();
}

@Override
Expand Down