Skip to content

Commit

Permalink
Merge branch 'shooterprototypetest' into main
Browse files Browse the repository at this point in the history
  • Loading branch information
s-aditya-k committed Jan 12, 2024
2 parents 41cda82 + 274f5a7 commit f9aa9a8
Show file tree
Hide file tree
Showing 5 changed files with 135 additions and 37 deletions.
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,9 @@ public final class Constants {

public static final class HardwarePorts {
// motors (predicted) IDs not fixed
public static final int shooterLeaderMotor = 1;
public static final int shooterFollowerMotor = 2;
// shooter ports should be correct, climb IDs still predicted
public static final int shooterLeaderM = 21;
public static final int shooterFollowerM = 22;
public static final int climbLeaderMotor = 3;
public static final int climbFollowerMotor = 4;

Expand Down
66 changes: 37 additions & 29 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,46 +5,54 @@
package frc.robot;

import frc.robot.Constants.OperatorConstants;
import frc.robot.commands.TossCommand;
import frc.robot.subsystems.ShooterSubsystem;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
* subsystems, commands, and trigger mappings) should be declared here.
*/
public class RobotContainer {
// The robot's subsystems and commands are defined here...

/* Controllers */
private final CommandXboxController driver = new CommandXboxController(0);
private final CommandXboxController operator = new CommandXboxController(1);

// Replace with CommandPS4Controller or CommandJoystick if needed
private final CommandXboxController m_driverController =
new CommandXboxController(OperatorConstants.kDriverControllerPort);
/* Driver Joysticks (drive control) */

/* Driver Buttons */


/* Operator Buttons */

/* Operator Sticks */

/* Subsystems */
private final ShooterSubsystem s_shooterSubsystem;

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
// Configure the trigger bindings

// Initialize subsystems
s_shooterSubsystem = ShooterSubsystem.getInstance();


// Configure the button bindings
configureBindings();
}

/**
* Use this method to define your trigger->command mappings. Triggers can be created via the
* {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary
* predicate, or via the named factories in {@link
* edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for {@link
* CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller
* PS4} controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight
* joysticks}.
*/
private void configureBindings() {}

/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
* @return the command to run in autonomous
*/
/* Map commands to buttons */
private void configureBindings() {

// driver controls
driver.a().whileTrue(new TossCommand());

// operator controls

}

public Command getAutonomousCommand() {
return null;
return null; // TODO fix
}
}
8 changes: 2 additions & 6 deletions src/main/java/frc/robot/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,10 @@ swerve module objects, used by the swerve drivetrain library we use (team 364)
import frc.lib.util.CTREModuleState;
import frc.lib.util.SwerveModuleConstants;

import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.controls.PositionDutyCycle;
import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.controls.VelocityDutyCycle;
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;

Expand All @@ -26,8 +24,6 @@ public class SwerveModule {

// Control requests
// Reuse these, don't make more
final DutyCycleOut dutyCycleRequest = new DutyCycleOut(0);
final VoltageOut voltageOutRequest = new VoltageOut(0);
// ControlMode.Position without voltage compensation
final PositionDutyCycle positionDutyCycleRequest = new PositionDutyCycle(0);
// ControlMode.Position with voltage compensation
Expand Down Expand Up @@ -76,10 +72,10 @@ public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop){
private void setSpeed(SwerveModuleState desiredState, boolean isOpenLoop){
if(isOpenLoop){
double percentOutput = desiredState.speedMetersPerSecond / Constants.SwerveConstants.maxSpeed;
mDriveMotor.setControl(dutyCycleRequest.withOutput(percentOutput));
mDriveMotor.set(percentOutput);
}
else {
double velocity = Conversions.MPSToFalcon(desiredState.speedMetersPerSecond, Constants.SwerveConstants.wheelCircumference, Constants.SwerveConstants.driveGearRatio);
double velocity = Conversions.MPSToFalcon(desiredState.speedMetersPerSecond, Constants.SwerveConstants.wheelCircumference, Constants.SwerveConstants.driveGearRatio);
mDriveMotor.setControl(velocityDutyCycle.withVelocity(velocity));
}
}
Expand Down
39 changes: 39 additions & 0 deletions src/main/java/frc/robot/commands/TossCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
// 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;

import frc.robot.subsystems.ShooterSubsystem;
import edu.wpi.first.wpilibj2.command.Command;

/** An example command that uses an example subsystem. */
public class TossCommand extends Command {
private final ShooterSubsystem s_shooter;
private boolean finish;

public TossCommand() {
s_shooter = ShooterSubsystem.getInstance();
addRequirements(s_shooter);
finish = false;
}

@Override
public void initialize() {}

@Override
public void execute() {
s_shooter.setVoltage(10);
finish = true;
}

@Override
public void end(boolean interrupted) {
s_shooter.setVoltage(0);
}

@Override
public boolean isFinished() {
return finish;
}
}
54 changes: 54 additions & 0 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
// 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;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import com.ctre.phoenix6.controls.StrictFollower;
import com.ctre.phoenix6.hardware.TalonFX;

public class ShooterSubsystem extends SubsystemBase {

private static ShooterSubsystem instance;
public static ShooterSubsystem getInstance() {
if (instance == null)
instance = new ShooterSubsystem();
return instance;
}

private TalonFX shooterLeaderM;
private TalonFX shooterFollowerM;

private double voltage;

public ShooterSubsystem() {
shooterLeaderM = new TalonFX(Constants.HardwarePorts.shooterLeaderM);
shooterFollowerM = new TalonFX(Constants.HardwarePorts.shooterFollowerM);
shooterFollowerM.setInverted(true);
shooterFollowerM.setControl(new StrictFollower(Constants.HardwarePorts.shooterLeaderM));
}


public void setVoltage(double voltage) {
this.voltage = voltage;
shooterLeaderM.setVoltage(voltage);
}

public double getVoltageSetpoint() {
return voltage;
}

@Override
public void periodic() {
SmartDashboard.putNumber("Motor Voltage Setpoint", getVoltageSetpoint());
}

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

0 comments on commit f9aa9a8

Please sign in to comment.