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 5 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
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 @@ -197,4 +197,11 @@ public static class Vision {

public static final Pose2d target = new Pose2d(1, 1, new Rotation2d(Units.degreesToRadians(0)));
}

public static class FeederConstants{

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

}
}
34 changes: 34 additions & 0 deletions src/main/java/frc/robot/commands/FeedShooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
// 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.wpilibj2.command.InstantCommand;

import frc.robot.subsystems.FeederSubsystem;

import frc.robot.Constants.FeederConstants;;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class FeedShooter extends InstantCommand {

// feeder subsystem
private FeederSubsystem feeder;

// constructor
public FeedShooter(FeederSubsystem feeder) {
addRequirements(feeder);
this.feeder = feeder;
}

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

}
}
33 changes: 33 additions & 0 deletions src/main/java/frc/robot/commands/FeederSetSpeed.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
// 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 com.ctre.phoenix.motorcontrol.TalonSRXSimCollection;

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

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class FeederSetSpeed extends InstantCommand {
// variables
private FeederSubsystem feeder;// feeder subsystem
double speed;

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

// Called when the command is initially scheduled.
@Override
public void initialize() {
// set speed to motor
feeder.setSpeed(speed);
}
}
46 changes: 46 additions & 0 deletions src/main/java/frc/robot/subsystems/FeederSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// 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.DemandType;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import com.fasterxml.jackson.annotation.JsonCreator.Mode;

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
}
}