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

Feeder #10

Merged
merged 6 commits into from
Jan 20, 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
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -304,4 +304,10 @@ public static class CollectingConstants{
public static final int SwitchID=1;
public static final int CollectingMotorID=10;
}
public static class FeederConstants{

public static final int FeederMotorId = 3;
public static final double FeederMotorSpeed = 0.8;

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
package frc.robot.commands.CollectingCommands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.CollectingConstants;
import frc.robot.subsystems.CollectingSubsystem;

public class setSpeedUntilFeedCommand extends Command {
Expand Down
30 changes: 30 additions & 0 deletions src/main/java/frc/robot/commands/feederCommands/FeedShooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
// 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.feederCommands;

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

import frc.robot.subsystems.FeederSubsystem;

import frc.robot.Constants.FeederConstants;;

public class FeedShooter extends InstantCommand {

// feeder subsystem
private FeederSubsystem feeder = FeederSubsystem.getInstance();

// constructor
public FeedShooter() {
addRequirements(feeder);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
// set speed to motor
feeder.setSpeed(FeederConstants.FeederMotorSpeed);

}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
// 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.feederCommands;

import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.robot.subsystems.FeederSubsystem;

public class FeederSetSpeed extends InstantCommand {
// variables
private FeederSubsystem feeder = FeederSubsystem.getInstance();// feeder subsystem
double speed;

// constructor
public FeederSetSpeed(double speed) {
addRequirements(feeder);
this.speed = speed;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
// set speed to motor
feeder.setSpeed(speed);
}
}
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/subsystems/CollectingSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@

import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import com.ctre.phoenix6.hardware.TalonFX;

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

Expand Down
43 changes: 43 additions & 0 deletions src/main/java/frc/robot/subsystems/FeederSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
// 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.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

import static frc.robot.Constants.FeederConstants.*;

public class FeederSubsystem extends SubsystemBase {
/** Creates a new FeederSubsystem. */

//the feeder's motor
TalonSRX m_Feeder;

//constructor
private FeederSubsystem(){
m_Feeder = new TalonSRX(FeederMotorId);
}

// singelton
private static FeederSubsystem instance;

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

// set speed function
public void setSpeed(double motorSpeed){
m_Feeder.set(ControlMode.PercentOutput, motorSpeed);
}

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