Skip to content

Commit

Permalink
chore: minor bugfixes and cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
ArnoUUU committed Feb 21, 2024
1 parent fd6d287 commit 0965a64
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 17 deletions.
3 changes: 0 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,11 @@

package frc.robot;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc.robot.Constants.IntakeConstants;
import frc.robot.subsystems.IntakeSubsystem;
Expand Down
32 changes: 18 additions & 14 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,19 +9,20 @@

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.Constants.IntakeConstants;

//creates new motors and pid controllers lmao

public class IntakeSubsystem extends SubsystemBase {
CANSparkFlex intakeMotor = new CANSparkFlex(IntakeConstants.kIntakeMotorID, MotorType.kBrushless);
CANSparkFlex armMotor = new CANSparkFlex(IntakeConstants.kArmMotorID, MotorType.kBrushless);
CANSparkFlex m_intakeMotor = new CANSparkFlex(IntakeConstants.kIntakeMotorID, MotorType.kBrushless);
CANSparkFlex m_armMotor = new CANSparkFlex(IntakeConstants.kArmMotorID, MotorType.kBrushless);

PIDController intakeVeloPID = new PIDController(IntakeConstants.kIntakeP, IntakeConstants.kIntakeI,
PIDController m_intakeVeloPID = new PIDController(IntakeConstants.kIntakeP, IntakeConstants.kIntakeI,
IntakeConstants.kIntakeD);
PIDController armPID = new PIDController(IntakeConstants.kArmP, IntakeConstants.kArmI, IntakeConstants.kArmD);
DutyCycleEncoder armEncoder = new DutyCycleEncoder(IntakeConstants.kArmEncoderCh);
PIDController m_armPID = new PIDController(IntakeConstants.kArmP, IntakeConstants.kArmI, IntakeConstants.kArmD);

DutyCycleEncoder m_armEncoder = new DutyCycleEncoder(IntakeConstants.kArmEncoderCh);

/** Creates a new intake. */
public IntakeSubsystem() {
Expand All @@ -30,29 +31,32 @@ public IntakeSubsystem() {

// Starts intaking the disk
public void intakeDisk() {
intakeMotor.set(IntakeConstants.kIntakeSpeed);
m_intakeMotor.set(IntakeConstants.kIntakeSpeed);
}

//
//Stops rotating the intake
public void stopIntaking() {
intakeMotor.set(0);
m_intakeMotor.set(0);
}

/**
*
* Rotates the arm to a given angle
* @param angle motor to apply to intake
*
*/
public void tiltToAngle(double angle) {
double motorPower = armPID.calculate(armEncoder.getAbsolutePosition(), angle);
armMotor.set(motorPower);
m_armMotor.set(m_armPID.calculate(m_armEncoder.getAbsolutePosition(), angle));
}

//Stops rotating the arm
public void stopRotating(){

m_armMotor.set(0);
}

@Override
public void periodic() {
SmartDashboard.putBoolean("Intake",m_intakeMotor.get()>0);

// This method will be called once per scheduler run
}
}

0 comments on commit 0965a64

Please sign in to comment.