Skip to content

Commit

Permalink
joystick control start
Browse files Browse the repository at this point in the history
  • Loading branch information
WispySparks committed Sep 10, 2024
1 parent dca0b48 commit a8a5cf6
Show file tree
Hide file tree
Showing 4 changed files with 92 additions and 0 deletions.
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,4 +32,8 @@ public static class SwerveK {

public static final File swerveDirectory = new File(Filesystem.getDeployDirectory().getAbsolutePath() + "/swerve");
}

public static class ControllerK {
public static final int xboxPort = 0; //! Find
}
}
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,21 @@
package frc.robot;

import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.Constants.ControllerK;
import frc.robot.subsystems.Swerve;

public class Robot extends TimedRobot {

private final Swerve swerve = new Swerve();

final CommandXboxController xboxController = new CommandXboxController(ControllerK.xboxPort);

public Robot() {
configureController();
}

private void configureController() {

}

Expand Down
70 changes: 70 additions & 0 deletions src/main/java/frc/robot/commands/AbsoluteDriveAdv.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
package frc.robot.commands;

import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;

import frc.robot.subsystems.Swerve;

public class AbsoluteDriveAdv {

private final Swerve swerve;
private final DoubleSupplier vX, vY, headingAdjust;
private final BooleanSupplier lookAway, lookTowards, lookLeft, lookRight;
private boolean resetHeading;

/**
* @param swerve Swerve Subsystem
* @param vX Double supplier X component of joystick input after deadband is applied, should be -1 to 1
* @param vY Double supplier Y component of joystick input after deadband is applied, should be -1 to 1
* @param headingAdjust Double supplier current robot heading to be adjusted after deadband is applied
* @param lookAway Faces the robot towards the opposind alliance wall from the driver
* @param lookTowards Faces the robot towards the driver
* @param lookLeft Faces the robot left
* @param lookRight Faces the robot right
*
* @return
*/
public AbsoluteDriveAdv(Swerve swerve, DoubleSupplier vX, DoubleSupplier vY, DoubleSupplier headingAdjust,
BooleanSupplier lookAway, BooleanSupplier lookTowards, BooleanSupplier lookLeft,
BooleanSupplier lookRight) {

this.swerve = swerve;
this.vX = vX;
this.vY = vY;
this.headingAdjust = headingAdjust;
this.lookAway = lookAway;
this.lookTowards = lookTowards;
this.lookLeft = lookLeft;
this.lookRight = lookRight;
}

public void initialize() {
resetHeading = true;
}

public void execute() {
double headingX = 0; // Resets values
double headingY = 0;

if (lookAway.getAsBoolean()) { // Y
headingY = -1;
}
if (lookTowards.getAsBoolean()) { // Y
headingY = 1;
}
if (lookLeft.getAsBoolean()) { // X
headingX = -1;
}
if (lookRight.getAsBoolean()) { // X
headingX = 1;
}
}

public void end() {

}

public boolean isFinished() {
return false; //!
}
}
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;

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.math.kinematics.ChassisSpeeds;
import edu.wpi.first.units.Angle;
Expand Down Expand Up @@ -119,4 +120,13 @@ public ChassisSpeeds getRobotVelocity() {
public void setChassisSpeeds(ChassisSpeeds chassisSpeeds) {
swerveDrive.setChassisSpeeds(chassisSpeeds);
}

public Rotation2d getHeading() {
return getPose().getRotation();
}

public ChassisSpeeds getTargetChassisSpeeds(double xInput, double yInput, Rotation2d angle) {
Translation2d scaledInputs = SwerveMath.cubeTranslation(new Translation2d(xInput, yInput));
return swerveDrive.swerveController.getTargetSpeeds(scaledInputs.getX(), scaledInputs.getY(), angle.getRadians(), getPose().getRotation().getRadians(), SwerveK.maxModuleSpeed.in(MetersPerSecond));
}
}

0 comments on commit a8a5cf6

Please sign in to comment.