Skip to content

Commit

Permalink
Added feeder subsystem
Browse files Browse the repository at this point in the history
  • Loading branch information
stebb1976 committed Apr 11, 2021
1 parent 425cadb commit 1e962a0
Show file tree
Hide file tree
Showing 9 changed files with 247 additions and 15 deletions.
10 changes: 9 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,17 @@ public class Constants {
public static final int[] RIGHT_DRIVETRAIN_SLAVES = new int[]{4};

//Intake
public static final int INTAKE_MOTOR = 0;
public static final int INTAKE_MOTOR = 20;
public static final int INTAKE_DEPLOY = 7;//deploy and retract are pneumatic ids
public static final int INTAKE_RETRACT = 3;

//Flywheel
public static final int FLYWHEEL_LEFT = 15;
public static final int FLYWHEEL_RIGHT = 16;

//Feeder
public static final int KICKER = 11;
public static final int FEEDER = 9;

//v belt id = 7
//feeder id = 9
Expand Down
17 changes: 11 additions & 6 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
import frc.robot.commands.ExampleCommand;
import frc.robot.commands.Drivetrain.ArcadeDrive;
import frc.robot.commands.Drivetrain.CharacterizeDrivetrain;
import frc.robot.commands.Flywheel.CharacterizeFlywheel;
import frc.robot.commands.Flywheel.FlywheelToSpeed;
import frc.robot.commands.Intake.IntakeDeploy;
import frc.robot.commands.Intake.IntakeSpit;
import frc.robot.commands.Intake.IntakeSuck;
Expand All @@ -23,6 +25,7 @@
import frc.robot.commands.Lift.LiftToHeight;
import frc.robot.commands.Lift.LiftUp;
import frc.robot.subsystems.DifferentialDrivetrain;
import frc.robot.subsystems.Flywheel;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.Lift;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -54,15 +57,16 @@ public class RobotContainer {

private final Lift m_lift = new Lift();
private final Intake m_intake = new Intake();
private final Flywheel m_flywheel = new Flywheel();

private final ExampleCommand m_autoCommand = new ExampleCommand();

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {

m_drivetrain.configFeedforwardSided(
-0.189290699848, -0.293030735327, -0.000429988610686,
-0.170613477504, -0.304934237999, 0.0020575793998);
-0.236065840797, -1.2349960266, 0.00891040293398,
-0.230709327857, -1.24552774756, -0.0146211933272);
//m_drivetrain.configRotationFeedForward(kS, kV, kA);Do this
//m_lift.setDefaultCommand(new LiftRetract(m_lift));
m_drivetrain.setDefaultCommand(new ArcadeDrive(m_drivetrain, m_controller, 1, Math.PI / 2));
Expand All @@ -86,9 +90,10 @@ private void configureButtonBindings() {
new JoystickButton(m_buttonbox, 5).whenPressed(new LiftToHeight(m_lift, 1));
new JoystickButton(m_buttonbox, 6).whenPressed(new LiftToHeight(m_lift, 0));
//
//new JoystickButton(m_controller, 0/* button label */).whileHeld(new IntakeSuck(m_intake));
//new JoystickButton(m_controller, 0/* button label */).whileHeld(new IntakeSpit(m_intake));

//new JoystickButton(m_buttonbox, 7/* button label */).whileHeld(new IntakeSuck(m_intake));
//new JoystickButton(m_buttonbox, 8/* button label */).whileHeld(new IntakeSpit(m_intake));
new JoystickButton(m_buttonbox, 7).whenPressed(new FlywheelToSpeed(m_flywheel, 80));
new JoystickButton(m_buttonbox, 8).whenPressed(new FlywheelToSpeed(m_flywheel, 0));
}

/**
Expand All @@ -97,7 +102,7 @@ private void configureButtonBindings() {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
return new CharacterizeDrivetrain(m_drivetrain);
return new CharacterizeFlywheel(m_flywheel);//new CharacterizeDrivetrain(m_drivetrain);
//return new ExampleCommand();
}
}
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/Utility/Motor.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ public Motor(int id, MotorType motorType) {
case TalonFX:
m_talonFX = new WPI_TalonFX(id);
m_talonFX.configSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor);
m_talonSRX.setSelectedSensorPosition(0);
m_talonFX.setSelectedSensorPosition(0);
break;

case VictorSPX:
Expand Down Expand Up @@ -153,7 +153,7 @@ public double getVelocity() {
return (double) m_talonSRX.getSelectedSensorVelocity() / 4096.0 * 10.0;

case TalonFX:
return (double) m_talonSRX.getSelectedSensorVelocity() / 2048.0 * 10.0;
return (double) m_talonFX.getSelectedSensorVelocity() / 2048.0 * 10.0;

case VictorSPX:
return Double.NaN;
Expand All @@ -172,7 +172,7 @@ public double getPosition() {
return (double) m_talonSRX.getSelectedSensorPosition() / 4096.0;

case TalonFX:
return (double) m_talonSRX.getSelectedSensorPosition() / 2048.0;
return (double) m_talonFX.getSelectedSensorPosition() / 2048.0;

case VictorSPX:
return Double.NaN;
Expand Down Expand Up @@ -241,12 +241,12 @@ public void setInverted(boolean isInverted){
}

if (m_motorType == MotorType.TalonFX) {
if(m_talonSRX.getControlMode() != com.ctre.phoenix.motorcontrol.ControlMode.Follower)
if(m_talonFX.getControlMode() != com.ctre.phoenix.motorcontrol.ControlMode.Follower)
m_talonFX.setInverted(isInverted);
}

if (m_motorType == MotorType.VictorSPX) {
if(m_talonSRX.getControlMode() != com.ctre.phoenix.motorcontrol.ControlMode.Follower)
if(m_victorSPX.getControlMode() != com.ctre.phoenix.motorcontrol.ControlMode.Follower)
m_victorSPX.setInverted(isInverted);
}

Expand All @@ -262,7 +262,7 @@ public void resetEncoder(){
}

if (m_motorType == MotorType.TalonFX) {
m_talonSRX.setSelectedSensorPosition(0);
m_talonFX.setSelectedSensorPosition(0);
}

if (m_motorType == MotorType.CANSparkMax) {
Expand Down
41 changes: 41 additions & 0 deletions src/main/java/frc/robot/commands/Feeder/PrepareAmmo.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// 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.Feeder;

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.Constants;
import frc.robot.subsystems.Feeder;

public class PrepareAmmo extends CommandBase {
Feeder m_feeder;
/** Creates a new PrepareAmmo. */
public PrepareAmmo(Feeder feeder) {
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(feeder);
m_feeder = feeder;
}

// 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() {
m_feeder.enableFeeder();
}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
// 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.Flywheel;

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.Flywheel;

public class CharacterizeFlywheel extends CommandBase {
Flywheel m_flywheel;
double m_voltage;
double m_pastVelocity;
/** Creates a new CharacterizeFlywheel. */
public CharacterizeFlywheel(Flywheel flywheel) {
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(flywheel);
m_flywheel = flywheel;
}

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

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_flywheel.setVoltage(m_voltage);

System.out.printf("%f", m_voltage);
System.out.print(",");
System.out.printf("%f", m_flywheel.getVelocity());
System.out.print(",");
System.out.printf("%f", (m_flywheel.getVelocity() - m_pastVelocity) / (20.0 / 1000.0) /* deltatime */);
System.out.println();
m_voltage += 0.01;
m_pastVelocity = m_flywheel.getVelocity();
}

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

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

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.Flywheel;

public class FlywheelToSpeed extends CommandBase {
Flywheel m_flywheel;
double m_speed;
/** Creates a new FlywheelToSpeed. */
public FlywheelToSpeed(Flywheel flywheel,double speed) {
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(flywheel);
m_flywheel = flywheel;
m_speed = speed;
}

// 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() {
m_flywheel.setVelocity(m_speed);
//System.out.println(m_flywheel.getVelocity());
}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -169,8 +169,8 @@ public void setArcadeDrive(double speed, double rotation){
setLeftTarget(speed + rotationVelocity);
setRightTarget(speed - rotationVelocity);
}else{
setLeftTarget(speed + rotation);
setRightTarget(speed - rotation);
setLeftTarget(-(speed + rotation));
setRightTarget(-(speed - rotation));
}
}

Expand Down
43 changes: 43 additions & 0 deletions src/main/java/frc/robot/subsystems/Feeder.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 edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.Utility.Motor;
import frc.robot.Utility.Motor.ControlMode;
import frc.robot.Utility.Motor.MotorType;

public class Feeder extends SubsystemBase {
private Motor m_kicker = new Motor(Constants.KICKER, MotorType.CANSparkMax);
private Motor m_feeder = new Motor(Constants.FEEDER, MotorType.CANSparkMax);

/** Creates a new Feeder. */
public Feeder() {
m_kicker.enableBrakeMode(true);
m_feeder.enableBrakeMode(true);
}

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

public void enableKicker(){
m_kicker.set(ControlMode.PercentOutput, 1);
}

public void disableKicker(){
m_kicker.set(ControlMode.PercentOutput, 0);
}

public void enableFeeder(){
m_feeder.set(ControlMode.PercentOutput, 1);
}

public void disableFeeder(){
m_feeder.set(ControlMode.PercentOutput, 0);
}
}
41 changes: 41 additions & 0 deletions src/main/java/frc/robot/subsystems/Flywheel.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// 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 edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.Utility.Motor;
import frc.robot.Utility.Motor.ControlMode;
import frc.robot.Utility.Motor.MotorType;

public class Flywheel extends SubsystemBase {
private Motor m_left = new Motor(Constants.FLYWHEEL_LEFT, MotorType.TalonFX);
private Motor m_right = new Motor(Constants.FLYWHEEL_RIGHT, MotorType.TalonFX);

/** Creates a new Flywheel. */
public Flywheel() {
m_left.enableBrakeMode(false);
m_right.enableBrakeMode(false);
m_right.follow(m_left, true);
m_left.configFeedforward(0.606918644699, 0.10519315078, -0.0000948594470576);
}

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

public void setVoltage(double voltage){
m_left.set(ControlMode.Voltage, voltage);
}

public void setVelocity(double velocity){
m_left.set(ControlMode.Velocity, velocity);
}

public double getVelocity(){
return m_left.getVelocity();
}
}

0 comments on commit 1e962a0

Please sign in to comment.