Skip to content
This repository has been archived by the owner on Aug 28, 2024. It is now read-only.

Intake subsystem + commands for rotating intake wheels #6

Merged
merged 1 commit into from
Jan 31, 2024
Merged
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
11 changes: 10 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,22 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.Intake.IntakeIn;
import frc.robot.subsystems.Intake.Intake;

public class RobotContainer {
private final Intake intake;
private final CommandXboxController driverController;
public RobotContainer() {
intake = new Intake();
driverController = new CommandXboxController(0);
configureBindings();
}

private void configureBindings() {}
private void configureBindings() {
driverController.b().whileTrue(new IntakeIn(intake, 0.1));
}

public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
Expand Down
51 changes: 51 additions & 0 deletions src/main/java/frc/robot/commands/Intake/IntakeIn.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
// 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.Intake;

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

public class IntakeIn extends Command {
/** Creates a new IntakeIn. */
private final Intake c_intake;
private final double c_intakeVoltage;

public IntakeIn(Intake intake, double intakeVoltage) {
c_intake = intake;
c_intakeVoltage = intakeVoltage;

addRequirements(c_intake);
// use addRequirements( here to declare subsystem dependentc

}




// Called when the command is initially scheduled.
@Override
public void initialize() {

}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
c_intake.rotateIntakeWheels(c_intakeVoltage);

}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
44 changes: 44 additions & 0 deletions src/main/java/frc/robot/commands/Intake/RotateArm.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// 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.Intake;

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

public class RotateArm extends Command {
/** Creates a new RotateArm. */
private final Intake c_intake;
private final double c_angle;

public RotateArm(Intake intake, Double intakeAngle) {
c_intake = intake;
c_angle = intakeAngle;

addRequirements(c_intake);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
c_intake.rotateArm(c_angle);
}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
49 changes: 49 additions & 0 deletions src/main/java/frc/robot/subsystems/Intake/Intake.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.subsystems.Intake;

import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.controls.PositionDutyCycle;
import com.ctre.phoenix6.hardware.TalonFX;

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

public class Intake extends SubsystemBase {
private final TalonFX intakeWheel;
private final TalonFX intakeRotation;
private final TalonFX armRotation;
private final DutyCycleEncoder intakeRotationEncoder;
private final DutyCycleEncoder armRotationEncoder;

/** Creates a new Intake. */
public Intake() {
intakeWheel = new TalonFX(0);
intakeRotation = new TalonFX(0);
armRotation = new TalonFX(0);
intakeRotationEncoder = new DutyCycleEncoder(0);
armRotationEncoder = new DutyCycleEncoder(0);

}

public void rotateIntakeWheels(double c_intakeVoltage) {
DutyCycleOut power = new DutyCycleOut(0);
intakeWheel.setControl(power.withOutput(c_intakeVoltage));
}

public void rotateArm(double c_angle) {
PositionDutyCycle power = new PositionDutyCycle(0);
intakeWheel.setControl(power.withPosition(c_angle));
}

public double getIntakeRotationEncoderPosition() {
return intakeRotationEncoder.getAbsolutePosition();
}

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