Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

2 create a tankdrive subsystem v2 #16

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
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
6 changes: 6 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
Expand Up @@ -88,5 +88,11 @@
"buttonCount": 0,
"povCount": 0
}
],
"robotJoysticks": [
{
"guid": "78696e70757401000000000000000000",
"useGamepad": true
}
]
}
5 changes: 0 additions & 5 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,6 @@
"header": {
"open": true
}
},
"SPARK MAX [4]": {
"header": {
"open": true
}
}
}
},
Expand Down
39 changes: 33 additions & 6 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@

package frc.robot;

import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;
// import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
// import com.pathplanner.lib.util.PIDConstants;
// import com.pathplanner.lib.util.ReplanningConfig;
import com.revrobotics.CANSparkBase.IdleMode;

import edu.wpi.first.math.controller.HolonomicDriveController;
Expand All @@ -29,6 +29,23 @@
*/
public final class Constants {

public static final class TankDriveConstants {
public static final int kPilotXAxis = 1;
public static final int kPilotYAxis = 5;
public static final int kDriveModeButtonIdx = 6;

public static final double kDeadzone = 0.1;

public static final int kLeftDriveMotorPort1 = 1;
public static final int kLeftDriveMotorPort2 = 6;
public static final int kRightDriveMotorPort1 = 3;
public static final int kRightDriveMotorPort2 = 4;
public static final boolean kLeftDriveMotorReversed1 = true;
public static final boolean kLeftDriveMotorReversed2 = true;
public static final boolean kRightDriveMotorReversed1 = false;
public static final boolean kRightDriveMotorReversed2 = false;
}

public static final class DriveConstants {
// Driving Parameters - Note that these are not the maximum capable speeds of
// the robot, rather the allowed maximum speeds
Expand Down Expand Up @@ -68,6 +85,14 @@ public static final class DriveConstants {
public static final int kRearRightTurningCanId = 5;

public static final boolean kGyroReversed = false;

public static final double kPhysicalMaxSpeedMetersPerSecond = 5;
public static final double kPhysicalMaxAngularSpeedRadiansPerSecond = 2 * 2 * Math.PI;

public static final double kTeleDriveMaxSpeedMetersPerSecond = kPhysicalMaxSpeedMetersPerSecond / 4;
public static final double kTeleDriveMaxAngularSpeedRadiansPerSecond = kPhysicalMaxAngularSpeedRadiansPerSecond / 4;
public static final double kTeleDriveMaxAccelerationUnitsPerSecond = 3;
public static final double kTeleDriveMaxAngularAccelerationUnitsPerSecond = 3;
}

public static final class ModuleConstants {
Expand Down Expand Up @@ -145,9 +170,11 @@ public static final class IntakeContants {

public static final class AutoConstants {
public static final double maxModuleSpeed = 5;
public static final HolonomicPathFollowerConfig pathFollowerConfig = new HolonomicPathFollowerConfig(
new PIDConstants(0, 0, 0), new PIDConstants(0, 0, 0), 5, 0.565685, new ReplanningConfig()); // TODO: check
// driveBaseRadius
// public static final HolonomicPathFollowerConfig pathFollowerConfig = new
// HolonomicPathFollowerConfig(
// new PIDConstants(0, 0, 0), new PIDConstants(0, 0, 0), 5, 0.565685, new
// ReplanningConfig()); // TODO: check
// // driveBaseRadius
Comment on lines +173 to +177
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Did you need to comment these out? Are they being used anywhere?

}

public static final class ArmConstants {
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -72,13 +72,13 @@ public void disabledPeriodic() {
*/
@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
System.out.println(m_autonomousCommand);
// schedule the autonomous command (example)
if (m_autonomousCommand != null) {
// m_autonomousCommand = m_robotContainer.getAutonomousCommand();
// System.out.println(m_autonomousCommand);
// // schedule the autonomous command (example)
// if (m_autonomousCommand != null) {

m_autonomousCommand.schedule();
}
// m_autonomousCommand.schedule();
// }
}

/** This function is called periodically during autonomous. */
Expand Down
48 changes: 37 additions & 11 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,16 @@
import frc.robot.Constants.AutoConstants;
import frc.robot.Constants.DriveConstants;
import frc.robot.Constants.OIConstants;
import frc.robot.Constants.TankDriveConstants;
import frc.robot.commands.ArmJoystickCmd;
import frc.robot.commands.Autos;
import frc.robot.commands.IntakeButtonCmd;
import frc.robot.commands.SwerveJoystickCmd;
import frc.robot.commands.TankJoystickCmd;
import frc.robot.subsystems.ArmSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.Swerve.SwerveSubsystem;
import frc.robot.subsystems.TankDrive.TankDrive;

/**
* This class is where the bulk of the robot should be declared. Since
Expand All @@ -53,14 +56,27 @@ public class RobotContainer {
private final SendableChooser<Command> autoChooser;
private final SwerveSubsystem m_swerveSubsystem = new SwerveSubsystem();
private final IntakeSubsystem m_IntakeSubsystem = new IntakeSubsystem();
private final ArmSubsystem ArmSubsystem = new ArmSubsystem();
private final TankDrive tankSubsystem = new TankDrive();
private final Joystick driverJoytick = new Joystick(OIConstants.kDriverControllerPort);
private final Joystick copolietJoystick = new Joystick(OIConstants.kCopilotControllerPort);
private final Joystick copilotJoystick = new Joystick(OIConstants.kCopilotControllerPort);

/**
* The container for the robot. Contains subsystems, OI devices, and commands.
*/
public RobotContainer() {
// Uncomment to initialize each subsystem listed below
// swerveSubsystemInit();
// intakeSubsystemInit();
// armSubsystemInit();
Comment on lines +68 to +71
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

❤️

tankDriveInit();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

test your code. Then let's comment this out for the final commit before moving back to main.


configureBindings();
autoChooser = AutoBuilder.buildAutoChooser();
SmartDashboard.putData("Auto Chooser", autoChooser);
}

private void swerveSubsystemInit() {
m_swerveSubsystem.setDefaultCommand(new SwerveJoystickCmd(m_swerveSubsystem,
() -> -MathUtil.applyDeadband(driverJoytick.getRawAxis(OIConstants.kDriverXAxis),
OIConstants.kDeadband),
Expand All @@ -69,15 +85,27 @@ public RobotContainer() {
() -> -MathUtil.applyDeadband(driverJoytick.getRawAxis(OIConstants.kDriverRotAxis),
OIConstants.kDeadband),
true, true));
}

private void intakeSubsystemInit() {
m_IntakeSubsystem.setDefaultCommand(new IntakeButtonCmd(m_IntakeSubsystem, () -> driverJoytick.getRawButton(5),
() -> driverJoytick.getRawButton(6)));
// ArmSubsystem.setDefaultCommand(new ArmJoystickCmd(
// ArmSubsystem,
// () -> -ArmJoytick.getRawAxis(OIConstants.kDriverYAxis)));
}

configureBindings();
autoChooser = AutoBuilder.buildAutoChooser();
SmartDashboard.putData("Auto Chooser", autoChooser);
private void armSubsystemInit() {
ArmSubsystem
.setDefaultCommand(
new ArmJoystickCmd(ArmSubsystem, () -> copilotJoystick.getRawAxis(OIConstants.kDriverYAxis)));
}

private void tankDriveInit() {
tankSubsystem.setDefaultCommand(new TankJoystickCmd(
tankSubsystem,
() -> MathUtil.applyDeadband(driverJoytick.getRawAxis(TankDriveConstants.kPilotYAxis),
TankDriveConstants.kDeadzone),
() -> MathUtil.applyDeadband(driverJoytick.getRawAxis(TankDriveConstants.kPilotXAxis),
TankDriveConstants.kDeadzone),
() -> driverJoytick.getRawButtonPressed(TankDriveConstants.kDriveModeButtonIdx)));
}

/**
Expand All @@ -96,8 +124,8 @@ public RobotContainer() {
*/
private void configureBindings() {
// Schedule `ExampleCommand` when `exampleCondition` changes to `true`
// SmartDashboard.putData("Example Auto", Autos.followTestAuto());
// SmartDashboard.putData("Square Auto", Autos.followSquareAuto());
SmartDashboard.putData("Example Auto", Autos.followTestAuto());
SmartDashboard.putData("Square Auto", Autos.followSquareAuto());
}

/**
Expand All @@ -106,8 +134,6 @@ private void configureBindings() {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {

return autoChooser.getSelected();

}
}
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/commands/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ public static Command followTestAuto() {
public static Command followSquareAuto() {
return new PathPlannerAuto("Square Auto");
}

// Example auto command:
// public static Command exampleAuto(ExampleSubsystem subsystem) {
// return Commands.sequence(subsystem.exampleMethodCommand(), new
// ExampleCommand(subsystem));
Expand Down
64 changes: 64 additions & 0 deletions src/main/java/frc/robot/commands/TankJoystickCmd.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
package frc.robot.commands;

import java.util.function.Supplier;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.filter.SlewRateLimiter;
import frc.robot.Constants.DriveConstants;
import frc.robot.Constants.TankDriveConstants;
import frc.robot.subsystems.TankDrive.TankDrive;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.Trigger;

public class TankJoystickCmd extends Command {
// Initializes tankDrive subsystem, joystick x and y inputs, and drive mode
private final TankDrive tankSubsystem;
private final Supplier<Double> xInputFunction, yInputFunction;
private final Supplier<Boolean> driveModeFunction;
private final SlewRateLimiter xLimiter, yLimiter;
private Boolean toggle;

// Command constructor that takes in above parameters
public TankJoystickCmd(TankDrive tankSubsystem, Supplier<Double> xInputFunction, Supplier<Double> yInputFunction,
Supplier<Boolean> driveModeFunction) {
this.tankSubsystem = tankSubsystem;
this.xInputFunction = xInputFunction;
this.yInputFunction = yInputFunction;
this.driveModeFunction = driveModeFunction;
this.xLimiter = new SlewRateLimiter(DriveConstants.kTeleDriveMaxAccelerationUnitsPerSecond);
this.yLimiter = new SlewRateLimiter(DriveConstants.kTeleDriveMaxAccelerationUnitsPerSecond);
toggle = false;
addRequirements(tankSubsystem);
}

@Override
public void initialize() {
}

// Sets X/Y inputs to forward/turning motion if driveMode button is pressed, and
// left/right motion if not
@Override
public void execute() {
if (driveModeFunction.get()) {
toggle = !toggle;
}
if (toggle) {
tankSubsystem
.setInputForward(-MathUtil.applyDeadband(xInputFunction.get(), TankDriveConstants.kDeadzone));
tankSubsystem.setInputTurn(MathUtil.applyDeadband(yInputFunction.get(), TankDriveConstants.kDeadzone));
} else {
tankSubsystem.setInputLeft(-MathUtil.applyDeadband(xInputFunction.get(), TankDriveConstants.kDeadzone));
tankSubsystem
.setInputRight(MathUtil.applyDeadband(yInputFunction.get(), TankDriveConstants.kDeadzone));
}
}

@Override
public void end(boolean interrupted) {
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import java.util.function.Supplier;

import com.kauailabs.navx.frc.AHRS;
import com.pathplanner.lib.auto.AutoBuilder;
// import com.pathplanner.lib.auto.AutoBuilder;

import edu.wpi.first.wpilibj.ADIS16470_IMU;
import edu.wpi.first.wpilibj.SPI;
Expand Down Expand Up @@ -77,9 +77,9 @@ public SwerveSubsystem() {
}
}).start();
modules = new SwerveModule[] { m_frontLeft, m_frontRight, m_rearLeft, m_rearRight };
AutoBuilder.configureHolonomic(this::getPose, this::resetOdometry,
this::getSpeeds, this::driveRobotRelative,
AutoConstants.pathFollowerConfig, this::shouldFlipPath, this);
// AutoBuilder.configureHolonomic(this::getPose, this::resetOdometry,
// this::getSpeeds, this::driveRobotRelative,
// AutoConstants.pathFollowerConfig, this::shouldFlipPath, this);
}

@Override
Expand Down
81 changes: 81 additions & 0 deletions src/main/java/frc/robot/subsystems/TankDrive/TankDrive.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
// 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.subsystems.TankDrive;

import frc.robot.Constants.TankDriveConstants;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class TankDrive extends SubsystemBase {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's rename this to TankDriveSubsystem and the file as well. So we are consistent

// Initializes two motors on each side
private CANSparkMax leftMotor1, leftMotor2, rightMotor1, rightMotor2;

// Initializes forward, turning, left side and right side input vars
public double input_forward = 0;
public double input_turn = 0;
public double input_left = 0;
public double input_right = 0;

public TankDrive() {
// Defines motors from ports/ids from consts
leftMotor1 = new CANSparkMax(TankDriveConstants.kLeftDriveMotorPort1, MotorType.kBrushless);
leftMotor2 = new CANSparkMax(TankDriveConstants.kLeftDriveMotorPort2, MotorType.kBrushless);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So when looking at some other code I realized there is one last issue here.
Right now, you are telling both motors to spin at the same speed. And that "should" work. What we should do is tell one to follow the other.
leftMotor2.follow(leftMotor1);

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

rightMotor1 = new CANSparkMax(TankDriveConstants.kRightDriveMotorPort1, MotorType.kBrushless);
rightMotor2 = new CANSparkMax(TankDriveConstants.kRightDriveMotorPort2, MotorType.kBrushless);
leftMotor1.setInverted(TankDriveConstants.kLeftDriveMotorReversed1);
leftMotor2.setInverted(TankDriveConstants.kLeftDriveMotorReversed2);
rightMotor1.setInverted(TankDriveConstants.kRightDriveMotorReversed1);
rightMotor2.setInverted(TankDriveConstants.kRightDriveMotorReversed2);
}

@Override
public void periodic() {
// Defines fwd as left/right side moving in same direction, and turn as
// left/right side moving in opp direction
input_left = input_turn + input_forward;
input_right = input_turn - input_forward;

// Sets motor speeds to left/right input
leftMotor1.set(input_left);
leftMotor2.set(input_left);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't need this if they are set to follow above.

rightMotor1.set(input_right);
rightMotor2.set(input_right);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't need this if they are set to follow above.

}

// Methods for setting fwd/turn/left/right input
public void setInputForward(double forward) {
input_forward = forward;
}

public void setInputTurn(double turn) {
input_turn = turn;
}

public void setInputLeft(double left) {
leftMotor1.set(left);
leftMotor2.set(left);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't need this if they are set to follow above.

}

public void setInputRight(double right) {
rightMotor1.set(-right);
rightMotor2.set(-right);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't need this if they are set to follow above.

}

// Method for stopping all motors
public void stop() {
leftMotor1.set(0);
leftMotor2.set(0);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't need this if they are set to follow above.

rightMotor1.set(0);
rightMotor2.set(0);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't need this if they are set to follow above.

}

@Override
public void simulationPeriodic() {
// This method will be called once per scheduler run during simulation
}
}