Skip to content

Commit

Permalink
Conveyor Done
Browse files Browse the repository at this point in the history
(thanks shane i stole your code 😄 )
  • Loading branch information
Kendialouge committed Jan 28, 2024
1 parent 350a446 commit 9669b5e
Show file tree
Hide file tree
Showing 3 changed files with 103 additions and 0 deletions.
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,5 +76,12 @@ public static class MechanismConstants {
public static final boolean INTAKE_MOTOR_1_INVERTED = true;
public static final boolean INTAKE_MOTOR_2_INVERTED = false;
public static final double INTAKE_MOTOR_SPEED = 1;

// Conveyor Motors
public static final int CONVEYOR_MOTOR_1 = 22;
public static final int CONVEYOR_MOTOR_2 = 23;
public static final boolean CONVEYOR_MOTOR_1_INVERTED = true;
public static final boolean CONVEYOR_MOTOR_2_INVERTED = false;
public static final double CONVEYOR_MOTOR_SPEED = 1;
}
}
49 changes: 49 additions & 0 deletions src/main/java/frc/robot/commands/ConveyorCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
// 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 edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Conveyor;

public class ConveyorCommand extends Command {
private final Conveyor m_ConveyorSubsystem;
// controller
// TODO: Change this to the correct controller
private final Joystick ConveyorJoystick = new Joystick(1);

public ConveyorCommand(Conveyor subsystem) {
m_ConveyorSubsystem = subsystem;
addRequirements(m_ConveyorSubsystem);
}

@Override
public void initialize() {}

@Override
public void execute() {
// TODO: Change this to the correct button
if (ConveyorJoystick.getRawButton(3) == true) {

Check warning on line 28 in src/main/java/frc/robot/commands/ConveyorCommand.java

View workflow job for this annotation

GitHub Actions / qodana

Pointless boolean expression

`ConveyorJoystick.getRawButton(3) == true` can be simplified to 'ConveyorJoystick.getRawButton(3)'
m_ConveyorSubsystem.enableConveyor();
// TODO: Change this to the correct button
} else if (ConveyorJoystick.getRawButton(4) == true) {

Check warning on line 31 in src/main/java/frc/robot/commands/ConveyorCommand.java

View workflow job for this annotation

GitHub Actions / qodana

Pointless boolean expression

`ConveyorJoystick.getRawButton(4) == true` can be simplified to 'ConveyorJoystick.getRawButton(4)'
m_ConveyorSubsystem.reverseConveyor();
System.out.println("Conveyor Moving in Reverse");
} else {
m_ConveyorSubsystem.disableConveyor();
}
}

@Override
public void end(boolean interrupted) {
m_ConveyorSubsystem.disableConveyor();
m_ConveyorSubsystem.enableConveyor();
}

@Override
public boolean isFinished() {
return false;
}
}
47 changes: 47 additions & 0 deletions src/main/java/frc/robot/subsystems/Conveyor.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// 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 com.revrobotics.CANSparkLowLevel;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.MechanismConstants;

public class Conveyor extends SubsystemBase {

private final CANSparkMax conveyorMotor1 =
new CANSparkMax(MechanismConstants.CONVEYOR_MOTOR_1, CANSparkLowLevel.MotorType.kBrushless);
private final CANSparkMax conveyorMotor2 =
new CANSparkMax(MechanismConstants.CONVEYOR_MOTOR_2, CANSparkLowLevel.MotorType.kBrushless);

/** Creates a new Conveyor. */
public Conveyor() {
conveyorMotor1.setInverted(MechanismConstants.CONVEYOR_MOTOR_1_INVERTED);
conveyorMotor2.setInverted(MechanismConstants.CONVEYOR_MOTOR_2_INVERTED);
}

/** Sets the Conveyor motors to 100% power. */
public void enableConveyor() {
conveyorMotor1.set(MechanismConstants.CONVEYOR_MOTOR_SPEED);
conveyorMotor2.set(MechanismConstants.CONVEYOR_MOTOR_SPEED);
}

/** Sets the Conveyor motors to 0% power. */
public void disableConveyor() {
conveyorMotor1.set(0);
conveyorMotor2.set(0);
}

/** Sets the Conveyor motors to -100% power. (Reverse direction) */
public void reverseConveyor() {
conveyorMotor1.set(-MechanismConstants.CONVEYOR_MOTOR_SPEED);
conveyorMotor2.set(-MechanismConstants.CONVEYOR_MOTOR_SPEED);
}

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

0 comments on commit 9669b5e

Please sign in to comment.