-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
9 changed files
with
247 additions
and
15 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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; | ||
} | ||
} |
53 changes: 53 additions & 0 deletions
53
src/main/java/frc/robot/commands/Flywheel/CharacterizeFlywheel.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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
41
src/main/java/frc/robot/commands/Flywheel/FlywheelToSpeed.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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; | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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); | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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(); | ||
} | ||
} |