Compare commits
7 Commits
Author | SHA1 | Date | |
---|---|---|---|
|
4c49ad4e51 | ||
|
afe25cf046 | ||
|
eec4eee2ff | ||
|
15be1d67ea | ||
|
e4c7a12606 | ||
|
72da7b7d74 | ||
|
fd8ab8663b |
@ -6,13 +6,27 @@ package frc.robot;
|
||||
|
||||
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.command.BalayeuseAlgue;
|
||||
import frc.robot.command.BalayeuseCoral;
|
||||
import frc.robot.command.BalayeuseHaut;
|
||||
import frc.robot.command.L1Requin;
|
||||
import frc.robot.subsystems.Requin;
|
||||
|
||||
public class RobotContainer {
|
||||
CommandXboxController manette1 = new CommandXboxController(0);
|
||||
CommandXboxController manette2 = new CommandXboxController(0);
|
||||
Requin requin = new Requin();
|
||||
public RobotContainer() {
|
||||
configureBindings();
|
||||
}
|
||||
|
||||
private void configureBindings() {}
|
||||
private void configureBindings() {
|
||||
manette2.b().whileTrue(new BalayeuseAlgue(requin));
|
||||
manette2.x().whileTrue(new BalayeuseCoral(requin));
|
||||
manette2.y().whileTrue(new L1Requin(requin));
|
||||
manette2.rightBumper().whileTrue(new BalayeuseHaut(requin));
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
return Commands.print("No autonomous command configured");
|
||||
|
56
src/main/java/frc/robot/command/BalayeuseAlgue.java
Normal file
56
src/main/java/frc/robot/command/BalayeuseAlgue.java
Normal file
@ -0,0 +1,56 @@
|
||||
// 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.command;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Requin;
|
||||
|
||||
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
|
||||
public class BalayeuseAlgue extends Command {
|
||||
private Requin requin;
|
||||
/** Creates a new Balayeuse. */
|
||||
public BalayeuseAlgue(Requin requin) {
|
||||
this.requin = requin;
|
||||
addRequirements(requin);
|
||||
// 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() {
|
||||
if(requin.encodeur()>=500 && requin.encodeur()<=510){
|
||||
requin.rotationer(0);
|
||||
}
|
||||
else if(requin.encodeur()>=510){
|
||||
requin.rotationer(0.5);
|
||||
}
|
||||
else{
|
||||
requin.rotationer(-0.5);
|
||||
}
|
||||
if(requin.stop()){
|
||||
requin.balaye(0);
|
||||
}
|
||||
else{
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
requin.rotationer(0);
|
||||
requin.balaye(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
56
src/main/java/frc/robot/command/BalayeuseCoral.java
Normal file
56
src/main/java/frc/robot/command/BalayeuseCoral.java
Normal file
@ -0,0 +1,56 @@
|
||||
// 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.command;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Requin;
|
||||
|
||||
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
|
||||
public class BalayeuseCoral extends Command {
|
||||
private Requin requin;
|
||||
/** Creates a new Balayeuse. */
|
||||
public BalayeuseCoral(Requin requin) {
|
||||
this.requin = requin;
|
||||
addRequirements(requin);
|
||||
// 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() {
|
||||
if(requin.encodeur()>=100 && requin.encodeur()<=110){
|
||||
requin.rotationer(0);
|
||||
}
|
||||
else if(requin.encodeur()>=110){
|
||||
requin.rotationer(0.5);
|
||||
}
|
||||
else{
|
||||
requin.rotationer(-0.5);
|
||||
}
|
||||
if(requin.stop()){
|
||||
requin.balaye(0);
|
||||
}
|
||||
else{
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
requin.rotationer(0);
|
||||
requin.balaye(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
47
src/main/java/frc/robot/command/BalayeuseHaut.java
Normal file
47
src/main/java/frc/robot/command/BalayeuseHaut.java
Normal file
@ -0,0 +1,47 @@
|
||||
// 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.command;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Requin;
|
||||
|
||||
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
|
||||
public class BalayeuseHaut extends Command {
|
||||
private Requin requin;
|
||||
/** Creates a new Balayeuse. */
|
||||
public BalayeuseHaut(Requin requin) {
|
||||
this.requin = requin;
|
||||
addRequirements(requin);
|
||||
// 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() {
|
||||
if(requin.enHaut()==true){
|
||||
requin.rotationer(0);
|
||||
requin.reset();
|
||||
}
|
||||
else{
|
||||
requin.rotationer(0.5);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
requin.rotationer(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
56
src/main/java/frc/robot/command/L1Requin.java
Normal file
56
src/main/java/frc/robot/command/L1Requin.java
Normal file
@ -0,0 +1,56 @@
|
||||
// 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.command;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Requin;
|
||||
|
||||
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
|
||||
public class L1Requin extends Command {
|
||||
private Requin requin;
|
||||
/** Creates a new Balayeuse. */
|
||||
public L1Requin(Requin requin) {
|
||||
this.requin = requin;
|
||||
addRequirements(requin);
|
||||
// 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() {
|
||||
if(requin.encodeur()>=800 && requin.encodeur()<=810){
|
||||
requin.rotationer(0);
|
||||
}
|
||||
else if(requin.encodeur()>=810){
|
||||
requin.rotationer(0.5);
|
||||
}
|
||||
else{
|
||||
requin.rotationer(-0.5);
|
||||
}
|
||||
if(requin.stop()){
|
||||
requin.balaye(0);
|
||||
}
|
||||
else{
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
requin.rotationer(0);
|
||||
requin.balaye(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
43
src/main/java/frc/robot/subsystems/Requin.java
Normal file
43
src/main/java/frc/robot/subsystems/Requin.java
Normal file
@ -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.revrobotics.spark.SparkFlex;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Requin extends SubsystemBase {
|
||||
/** Creates a new Requin. */
|
||||
public Requin() {}
|
||||
final SparkFlex balaye = new SparkFlex(0, MotorType.kBrushless);
|
||||
final SparkMax rotatione = new SparkMax(0, MotorType.kBrushless);
|
||||
final DigitalInput limit3 = new DigitalInput(0);
|
||||
final DigitalInput limit5 = new DigitalInput(0);
|
||||
public void balaye(double vitesse){
|
||||
balaye.set(vitesse);
|
||||
}
|
||||
public void rotationer(double vitesse){
|
||||
rotatione.set(vitesse);
|
||||
}
|
||||
public boolean enHaut(){
|
||||
return limit3.get();
|
||||
}
|
||||
public boolean stop(){
|
||||
return limit5.get();
|
||||
}
|
||||
public double encodeur(){
|
||||
return rotatione.getEncoder().getPosition();
|
||||
}
|
||||
public void reset(){
|
||||
rotatione.getEncoder().setPosition(0);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
Loading…
x
Reference in New Issue
Block a user