Skip to content

Commit

Permalink
Merge pull request #111 from Technologyman00/New-Drive-Mode
Browse files Browse the repository at this point in the history
Adding Alternative Drive Mode for Rotation Shortcut Buttons and Right Stick Rotation Adjustment
  • Loading branch information
Technologyman00 authored Dec 15, 2023
2 parents f408236 + 20df778 commit 0d39234
Show file tree
Hide file tree
Showing 4 changed files with 171 additions and 2 deletions.
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,5 +48,7 @@ public static class OperatorConstants
// Joystick Deadband
public static final double LEFT_X_DEADBAND = 0.01;
public static final double LEFT_Y_DEADBAND = 0.01;
public static final double RIGHT_X_DEADBAND = 0.01;
public static final double TURN_CONSTANT = 0.75;
}
}
14 changes: 14 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
import frc.robot.commands.swervedrive.auto.Autos;
import frc.robot.commands.swervedrive.drivebase.AbsoluteDrive;
import frc.robot.commands.swervedrive.drivebase.AbsoluteFieldDrive;
import frc.robot.commands.swervedrive.drivebase.AbsoluteDriveAdv;
import frc.robot.commands.swervedrive.drivebase.TeleopDrive;
import frc.robot.subsystems.swervedrive.SwerveSubsystem;
import java.io.File;
Expand Down Expand Up @@ -66,6 +67,19 @@ public RobotContainer()
() -> MathUtil.applyDeadband(driverXbox.getLeftX(),
OperatorConstants.LEFT_X_DEADBAND),
() -> driverXbox.getRawAxis(2));

AbsoluteDriveAdv closedAbsoluteDriveAdv = new AbsoluteDriveAdv(drivebase,
() -> MathUtil.applyDeadband(driverXbox.getLeftY(),
OperatorConstants.LEFT_Y_DEADBAND),
() -> MathUtil.applyDeadband(driverXbox.getLeftX(),
OperatorConstants.LEFT_X_DEADBAND),
() -> MathUtil.applyDeadband(driverXbox.getRightX(),
OperatorConstants.RIGHT_X_DEADBAND),
driverXbox::getYButtonPressed,
driverXbox::getAButtonPressed,
driverXbox::getXButtonPressed,
driverXbox::getBButtonPressed);

TeleopDrive simClosedFieldRel = new TeleopDrive(drivebase,
() -> MathUtil.applyDeadband(driverXbox.getLeftY(),
OperatorConstants.LEFT_Y_DEADBAND),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package frc.robot.commands.swervedrive.drivebase;

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.wpilibj.smartdashboard.SmartDashboard;
Expand Down Expand Up @@ -80,10 +81,10 @@ public void execute()
if(headingHorizontal.getAsDouble() == 0 && headingVertical.getAsDouble() == 0)
{
// Get the curretHeading
double firstLoopHeading = swerve.getHeading().getRadians();
Rotation2d firstLoopHeading = swerve.getHeading();

// Set the Current Heading to the desired Heading
desiredSpeeds = swerve.getTargetSpeeds(0, 0, Math.sin(firstLoopHeading), Math.cos(firstLoopHeading));
desiredSpeeds = swerve.getTargetSpeeds(0, 0, firstLoopHeading.getSin(), firstLoopHeading.getCos());
}
//Dont Init Rotation Again
initRotation = false;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,152 @@
// 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.commands.swervedrive.drivebase;

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.networktables.BooleanSubscriber;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.Constants;
import frc.robot.subsystems.swervedrive.SwerveSubsystem;
import java.util.List;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import swervelib.SwerveController;
import swervelib.math.SwerveMath;

/**
* A more advanced Swerve Control System that has 4 buttons for which direction to face
*/
public class AbsoluteDriveAdv extends CommandBase
{

private final SwerveSubsystem swerve;
private final DoubleSupplier vX, vY;
private final DoubleSupplier headingAdjust;
private boolean initRotation = false;
private final BooleanSupplier lookAway, lookTowards, lookLeft, lookRight;

/**
* Used to drive a swerve robot in full field-centric mode. vX and vY supply translation inputs, where x is
* torwards/away from alliance wall and y is left/right. Heading Adjust changes the current heading after being
* multipied by a constant. The look booleans are shortcuts to get the robot to face a certian direction.
* Based off of ideas in https://www.chiefdelphi.com/t/experiments-with-a-swerve-steering-knob/446172
*
* @param swerve The swerve drivebase subsystem.
* @param vX DoubleSupplier that supplies the x-translation joystick input. Should be in the range -1
* to 1 with deadband already accounted for. Positive X is away from the alliance wall.
* @param vY DoubleSupplier that supplies the y-translation joystick input. Should be in the range -1
* to 1 with deadband already accounted for. Positive Y is towards the left wall when
* looking through the driver station glass.
* @param headingAdjust DoubleSupplier that supplies the component of the robot's heading angle that should be adjusted.
* Should range from -1 to 1 with deadband already accounted for.
* @param lookAway Face the robot towards the opposing alliance's wall in the same direction the driver is facing
* @param lookTowards Face the robot towards the driver
* @param lookLeft Face the robot left
* @param lookRight Face the robot right
*/
public AbsoluteDriveAdv(SwerveSubsystem 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;

addRequirements(swerve);
}

@Override
public void initialize()
{
initRotation = true;
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute()
{
double headingX = 0;
double headingY = 0;
Rotation2d newHeading = Rotation2d.fromRadians(0);

// These are written to allow combinations for 45 angles
// Face Away from Drivers
if(lookAway.getAsBoolean()){
headingX = 1;
}
// Face Right
if(lookRight.getAsBoolean()){
headingY = 1;
}
// Face Left
if(lookLeft.getAsBoolean()){
headingY = -1;
}
// Face Towards the Drivers
if(lookTowards.getAsBoolean()){
headingX = -1;
}

//Dont overwrite a button press
if(headingX == 0 && headingY == 0 && Math.abs(headingAdjust.getAsDouble()) > 0){
newHeading = Rotation2d.fromRadians(Constants.OperatorConstants.TURN_CONSTANT * -headingAdjust.getAsDouble())
.plus(swerve.getHeading());
headingX = newHeading.getSin();
headingY = newHeading.getCos();
}

ChassisSpeeds desiredSpeeds = swerve.getTargetSpeeds(vX.getAsDouble(), vY.getAsDouble(),
headingX,
headingY);

// Prevent Movement After Auto
if(initRotation)
{
if(headingX == 0 && headingY == 0)
{
// Get the curretHeading
Rotation2d firstLoopHeading = swerve.getHeading();

// Set the Current Heading to the desired Heading
desiredSpeeds = swerve.getTargetSpeeds(0, 0, firstLoopHeading.getSin(), firstLoopHeading.getCos());
}
//Dont Init Rotation Again
initRotation = false;
}

// Limit velocity to prevent tippy
Translation2d translation = SwerveController.getTranslation2d(desiredSpeeds);
translation = SwerveMath.limitVelocity(translation, swerve.getFieldVelocity(), swerve.getPose(),
Constants.LOOP_TIME, Constants.ROBOT_MASS, List.of(Constants.CHASSIS),
swerve.getSwerveDriveConfiguration());
SmartDashboard.putNumber("LimitedTranslation", translation.getX());
SmartDashboard.putString("Translation", translation.toString());

// Make the robot move
swerve.drive(translation, desiredSpeeds.omegaRadiansPerSecond, true);
}

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

// Returns true when the command should end.
@Override
public boolean isFinished()
{
return false;
}


}

0 comments on commit 0d39234

Please sign in to comment.