Compare commits
28 Commits
Author | SHA1 | Date | |
---|---|---|---|
abb6d113d0 | |||
df31291697 | |||
3b372104e4 | |||
36c9f0048b | |||
cdd304f9e9 | |||
1157bdf76a | |||
17f3f697b9 | |||
88aa6db075 | |||
d538b368a7 | |||
b6d2ffd931 | |||
f9d09106a4 | |||
0524ec6355 | |||
a09fbcefce | |||
7fd7c666f1 | |||
29227dd2f6 | |||
dc36eea320 | |||
eaa14fb1b1 | |||
3458203225 | |||
6683613c7f | |||
2ac9cfe8ff | |||
56704c3e68 | |||
4c49ad4e51 | |||
afe25cf046 | |||
eec4eee2ff | |||
15be1d67ea | |||
e4c7a12606 | |||
72da7b7d74 | |||
fd8ab8663b |
@ -1,7 +1,12 @@
|
|||||||
{
|
{
|
||||||
"System Joysticks": {
|
"FMS": {
|
||||||
"window": {
|
"window": {
|
||||||
"enabled": false
|
"visible": false
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"Joysticks": {
|
||||||
|
"window": {
|
||||||
|
"visible": false
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"keyboardJoysticks": [
|
"keyboardJoysticks": [
|
||||||
@ -93,5 +98,12 @@
|
|||||||
"buttonCount": 0,
|
"buttonCount": 0,
|
||||||
"povCount": 0
|
"povCount": 0
|
||||||
}
|
}
|
||||||
|
],
|
||||||
|
"robotJoysticks": [
|
||||||
|
{},
|
||||||
|
{
|
||||||
|
"guid": "78696e70757401000000000000000000",
|
||||||
|
"useGamepad": true
|
||||||
|
}
|
||||||
]
|
]
|
||||||
}
|
}
|
||||||
|
@ -9,37 +9,41 @@ import edu.wpi.first.wpilibj2.command.Command;
|
|||||||
import edu.wpi.first.wpilibj2.command.Commands;
|
import edu.wpi.first.wpilibj2.command.Commands;
|
||||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||||
import frc.robot.commands.GrimperHaut;
|
import frc.robot.commands.BalayeuseAlgue;
|
||||||
import frc.robot.commands.GrimpeurBas;
|
import frc.robot.commands.BalayeuseBas;
|
||||||
import frc.robot.commands.GrimpeurManuel;
|
import frc.robot.commands.BalayeuseCoral;
|
||||||
import frc.robot.commands.ResetGrimpeur;
|
import frc.robot.commands.BalayeuseHaut;
|
||||||
|
import frc.robot.commands.L1Requin;
|
||||||
|
import frc.robot.commands.aspire;
|
||||||
|
import frc.robot.commands.exspire;
|
||||||
|
import frc.robot.commands.requin_manuel;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
import frc.robot.subsystems.Bougie;
|
import frc.robot.subsystems.Bougie;
|
||||||
import frc.robot.subsystems.Grimpeur;
|
import frc.robot.commands.aspire;
|
||||||
|
|
||||||
public class RobotContainer {
|
public class RobotContainer {
|
||||||
CommandXboxController manette1 = new CommandXboxController(0);
|
CommandXboxController manette1 = new CommandXboxController(0);
|
||||||
CommandXboxController manette2 = new CommandXboxController(1);
|
CommandXboxController manette2 = new CommandXboxController(1);
|
||||||
Grimpeur grimpeur = new Grimpeur();
|
Requin requin = new Requin();
|
||||||
Bougie bougie = new Bougie();
|
Bougie bougie = new Bougie();
|
||||||
GrimpeurManuel grimpeurManuel = new GrimpeurManuel(grimpeur, manette2::getLeftY);
|
aspire aspire = new aspire(requin);
|
||||||
|
requin_manuel requin_manuel = new requin_manuel(requin);
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
grimpeur.setDefaultCommand(new RunCommand(()->{
|
|
||||||
if(grimpeur.stop()){
|
|
||||||
grimpeur.grimpe(0);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
grimpeur.grimpe(MathUtil.applyDeadband(manette2.getLeftY(), 0.2));
|
|
||||||
}}, grimpeur));
|
|
||||||
configureBindings();
|
configureBindings();
|
||||||
|
requin.setDefaultCommand(new RunCommand(()->{
|
||||||
|
requin.rotationer(MathUtil.applyDeadband(manette2.getRightY(), 0.2));
|
||||||
|
}, requin));
|
||||||
}
|
}
|
||||||
|
|
||||||
private void configureBindings() {
|
private void configureBindings() {
|
||||||
manette2.leftBumper().whileTrue(new GrimperHaut(grimpeur,bougie));
|
manette2.a().whileTrue(new aspire(requin));
|
||||||
manette2.rightBumper().whileTrue(new GrimpeurBas(grimpeur));
|
manette2.rightTrigger().whileTrue(new exspire(requin));
|
||||||
manette2.a().whileTrue(new ResetGrimpeur(grimpeur));
|
manette2.b().whileTrue(new BalayeuseAlgue(requin, bougie));
|
||||||
|
manette2.x().whileTrue(new BalayeuseCoral(requin, bougie));
|
||||||
|
manette2.y().whileTrue(new L1Requin(requin,bougie));
|
||||||
|
manette2.rightBumper().whileTrue(new BalayeuseHaut(requin));
|
||||||
}
|
}
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
return Commands.print("No autonomous command configured");
|
return Commands.print("No autonomous command configured");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
63
src/main/java/frc/robot/commands/BalayeuseAlgue.java
Normal file
63
src/main/java/frc/robot/commands/BalayeuseAlgue.java
Normal file
@ -0,0 +1,63 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Bougie;
|
||||||
|
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;
|
||||||
|
private Bougie bougie;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public BalayeuseAlgue(Requin requin, Bougie bougie) {
|
||||||
|
this.requin = requin;
|
||||||
|
this.bougie =bougie;
|
||||||
|
addRequirements(requin,bougie);
|
||||||
|
// 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);
|
||||||
|
if(requin.amp()> 60){
|
||||||
|
requin.balaye(0);
|
||||||
|
bougie.Vert();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
requin.balaye(0.5);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(requin.encodeur()>=510){
|
||||||
|
requin.rotationer(0.5);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(-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;
|
||||||
|
}
|
||||||
|
}
|
40
src/main/java/frc/robot/commands/BalayeuseBas.java
Normal file
40
src/main/java/frc/robot/commands/BalayeuseBas.java
Normal file
@ -0,0 +1,40 @@
|
|||||||
|
// 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.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 BalayeuseBas extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public BalayeuseBas(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() {
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
}
|
67
src/main/java/frc/robot/commands/BalayeuseCoral.java
Normal file
67
src/main/java/frc/robot/commands/BalayeuseCoral.java
Normal file
@ -0,0 +1,67 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Bougie;
|
||||||
|
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;
|
||||||
|
private Bougie bougie;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public BalayeuseCoral(Requin requin, Bougie bougie) {
|
||||||
|
this.requin = requin;
|
||||||
|
this.bougie = bougie;
|
||||||
|
addRequirements(requin,bougie);
|
||||||
|
// 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);
|
||||||
|
if(requin.amp()>60){
|
||||||
|
requin.balaye(0);
|
||||||
|
bougie.Vert();
|
||||||
|
if(requin.enHaut()){
|
||||||
|
requin.rotationer(0);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(0.5);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.balaye(0.5);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(requin.encodeur()>=110){
|
||||||
|
requin.rotationer(0.5);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(-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;
|
||||||
|
}
|
||||||
|
}
|
@ -5,15 +5,15 @@
|
|||||||
package frc.robot.commands;
|
package frc.robot.commands;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Grimpeur;
|
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 */
|
/* 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 GrimpeurBas extends Command {
|
public class BalayeuseHaut extends Command {
|
||||||
private Grimpeur grimpeur;
|
private Requin requin;
|
||||||
/** Creates a new GrimpeurBas. */
|
/** Creates a new Balayeuse. */
|
||||||
public GrimpeurBas(Grimpeur grimpeur) {
|
public BalayeuseHaut(Requin requin) {
|
||||||
this.grimpeur = grimpeur;
|
this.requin = requin;
|
||||||
addRequirements(grimpeur);
|
addRequirements(requin);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -24,20 +24,19 @@ public class GrimpeurBas extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(grimpeur.encodeur()>=-38.5 && grimpeur.encodeur()<=-39.19){
|
if(requin.enHaut()==true){
|
||||||
grimpeur.grimpe(0);
|
requin.rotationer(0);
|
||||||
|
requin.reset();
|
||||||
}
|
}
|
||||||
else if(grimpeur.encodeur()>=-38.5){
|
else{
|
||||||
grimpeur.grimpe(-0.5);
|
requin.rotationer(-0.5);
|
||||||
}
|
}
|
||||||
else{grimpeur.grimpe(0.5);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
grimpeur.grimpe(0);
|
requin.rotationer(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
41
src/main/java/frc/robot/commands/ExpireAlgue.java
Normal file
41
src/main/java/frc/robot/commands/ExpireAlgue.java
Normal file
@ -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;
|
||||||
|
|
||||||
|
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 ExpireAlgue extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
/** Creates a new ExpireAlgue. */
|
||||||
|
public ExpireAlgue(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() {
|
||||||
|
requin.balaye(0.5);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
@ -6,17 +6,17 @@ package frc.robot.commands;
|
|||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Bougie;
|
import frc.robot.subsystems.Bougie;
|
||||||
import frc.robot.subsystems.Grimpeur;
|
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 */
|
/* 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 GrimperHaut extends Command {
|
public class L1Requin extends Command {
|
||||||
private Grimpeur grimpeur;
|
private Requin requin;
|
||||||
private Bougie bougie;
|
private Bougie bougie;
|
||||||
/** Creates a new Grimper. */
|
/** Creates a new Balayeuse. */
|
||||||
public GrimperHaut(Grimpeur grimpeur, Bougie bougie) {
|
public L1Requin(Requin requin,Bougie bougie) {
|
||||||
this.grimpeur = grimpeur;
|
this.requin = requin;
|
||||||
this.bougie = bougie;
|
this.bougie = bougie;
|
||||||
addRequirements(grimpeur,bougie);
|
addRequirements(requin,bougie);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -27,30 +27,39 @@ public class GrimperHaut extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(grimpeur.stop()==true){
|
|
||||||
grimpeur.grimpe(0);
|
if(requin.encodeur()>=800 && requin.encodeur()<=810){
|
||||||
grimpeur.reset();
|
requin.rotationer(0);
|
||||||
bougie.RainBow();
|
if(requin.amp()>8){
|
||||||
|
requin.balaye(-0.5);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.balaye(0);
|
||||||
|
bougie.Rouge();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(requin.encodeur()>=810){
|
||||||
|
requin.rotationer(0.5);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
grimpeur.grimpe(0.5);
|
requin.rotationer(-0.5);
|
||||||
bougie.RainBowStop();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
grimpeur.grimpe(0);
|
requin.rotationer(0);
|
||||||
if(grimpeur.stop()){
|
requin.balaye(0);
|
||||||
bougie.RainBow();
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return grimpeur.stop()==true;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -5,16 +5,16 @@
|
|||||||
package frc.robot.commands;
|
package frc.robot.commands;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Bougie;
|
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 */
|
/* 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 RainBow extends Command {
|
public class aspire extends Command {
|
||||||
/** Creates a new RainBow. */
|
/** Creates a new aspire. */
|
||||||
private Bougie bougie;
|
private Requin requin;
|
||||||
public RainBow(Bougie bougie) {
|
public aspire(Requin requin) {
|
||||||
this.bougie = bougie;
|
|
||||||
addRequirements(bougie);
|
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@ -24,13 +24,13 @@ public class RainBow extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
bougie.RainBow();
|
requin.balaye(0.3);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
bougie.RainBowStop();
|
requin.balaye(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
@ -5,16 +5,16 @@
|
|||||||
package frc.robot.commands;
|
package frc.robot.commands;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Grimpeur;
|
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 */
|
/* 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 ResetGrimpeur extends Command {
|
public class exspire extends Command {
|
||||||
private Grimpeur grimpeur;
|
/** Creates a new aspire. */
|
||||||
/** Creates a new ResetGrimpeur. */
|
private Requin requin;
|
||||||
public ResetGrimpeur(Grimpeur grimpeur) {
|
public exspire(Requin requin) {
|
||||||
this.grimpeur = grimpeur;
|
|
||||||
addRequirements(grimpeur);
|
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@ -24,12 +24,14 @@ public class ResetGrimpeur extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
grimpeur.reset();
|
requin.balaye(-0.3);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {}
|
public void end(boolean interrupted) {
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
@ -7,18 +7,17 @@ package frc.robot.commands;
|
|||||||
import java.util.function.DoubleSupplier;
|
import java.util.function.DoubleSupplier;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import frc.robot.subsystems.Grimpeur;
|
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 */
|
/* 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 GrimpeurManuel extends Command {
|
public class requin_manuel extends Command {
|
||||||
private Grimpeur grimpeur;
|
/** Creates a new requin_manuel. */
|
||||||
|
private Requin requin;
|
||||||
private DoubleSupplier x;
|
private DoubleSupplier x;
|
||||||
/** Creates a new GrimpeurManuel. */
|
public requin_manuel(Requin requin) {
|
||||||
public GrimpeurManuel(Grimpeur grimpeur,DoubleSupplier x) {
|
|
||||||
this.grimpeur = grimpeur;
|
|
||||||
this.x = x;
|
|
||||||
addRequirements(grimpeur);
|
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@ -28,19 +27,18 @@ public class GrimpeurManuel extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(grimpeur.stop()){
|
if(requin.enHaut()){
|
||||||
grimpeur.grimpe(0);
|
requin.rotationer(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
grimpeur.grimpe(x.getAsDouble());
|
requin.rotationer(x.getAsDouble());
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
grimpeur.grimpe(0);
|
requin.rotationer(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
@ -11,7 +11,7 @@ import com.ctre.phoenix.led.RainbowAnimation;
|
|||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Bougie extends SubsystemBase {
|
public class Bougie extends SubsystemBase {
|
||||||
CANdle candle = new CANdle(5);
|
CANdle candle = new CANdle(23);
|
||||||
CANdleConfiguration config = new CANdleConfiguration();
|
CANdleConfiguration config = new CANdleConfiguration();
|
||||||
RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64);
|
RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64);
|
||||||
/** Creates a new Bougie. */
|
/** Creates a new Bougie. */
|
||||||
@ -20,19 +20,34 @@ public class Bougie extends SubsystemBase {
|
|||||||
candle.configAllSettings(config);
|
candle.configAllSettings(config);
|
||||||
}
|
}
|
||||||
public void Rouge() {
|
public void Rouge() {
|
||||||
candle.setLEDs(255, 0, 0);
|
candle.setLEDs(255, 0, 0,0,8,8);
|
||||||
|
candle.setLEDs(255, 0, 0,0,24,8);
|
||||||
|
candle.setLEDs(255, 0, 0,0,40,8);
|
||||||
|
candle.setLEDs(255, 0, 0,0,56,8);
|
||||||
}
|
}
|
||||||
public void Vert() {
|
public void Vert() {
|
||||||
candle.setLEDs(0, 255, 0);
|
candle.setLEDs(0, 255, 0,0,8,8);
|
||||||
|
candle.setLEDs(0, 255, 0,0,24,8);
|
||||||
|
candle.setLEDs(0, 255, 0,0,40,8);
|
||||||
|
candle.setLEDs(0, 255, 0,0,56,8);
|
||||||
}
|
}
|
||||||
public void Bleu() {
|
public void Bleu() {
|
||||||
candle.setLEDs(0, 0, 255);
|
candle.setLEDs(0, 0, 255,0,16,8);
|
||||||
|
candle.setLEDs(0, 0, 255,0,32,8);
|
||||||
|
candle.setLEDs(0, 0, 255,0,48,8);
|
||||||
|
candle.setLEDs(0, 0, 255,0,64,8);
|
||||||
}
|
}
|
||||||
public void RainBow(){candle.animate(rainbowAnim);}
|
public void Jaune() {
|
||||||
|
candle.setLEDs(255, 215, 0,0,16,8);
|
||||||
|
candle.setLEDs(255, 215, 0,0,32,8);
|
||||||
|
candle.setLEDs(255, 215, 0,0,48,8);
|
||||||
|
candle.setLEDs(255, 215, 0,0,64,8);
|
||||||
|
}
|
||||||
|
public void RainBow(){
|
||||||
|
candle.animate(rainbowAnim);}
|
||||||
public void RainBowStop(){candle.animate(null);}
|
public void RainBowStop(){candle.animate(null);}
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
// This method will be called once per scheduler run
|
// This method will be called once per scheduler run
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -4,35 +4,43 @@
|
|||||||
|
|
||||||
package frc.robot.subsystems;
|
package frc.robot.subsystems;
|
||||||
|
|
||||||
|
import com.revrobotics.spark.SparkFlex;
|
||||||
import com.revrobotics.spark.SparkMax;
|
import com.revrobotics.spark.SparkMax;
|
||||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Grimpeur extends SubsystemBase {
|
public class Requin extends SubsystemBase {
|
||||||
/** Creates a new Grimpeur. */
|
/** Creates a new Requin. */
|
||||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||||
public Grimpeur() {
|
public Requin() {
|
||||||
teb.addBoolean("limit grimpeur", this::stop);
|
teb.addBoolean("limit requin", this::enHaut);
|
||||||
teb.addDouble("encodeur grimpeur", this::encodeur);
|
|
||||||
}
|
}
|
||||||
final SparkMax grimpeur = new SparkMax(21,MotorType.kBrushless);
|
|
||||||
final DigitalInput limit1 = new DigitalInput(2);
|
final SparkFlex balaye = new SparkFlex(15, MotorType.kBrushless);
|
||||||
public void grimpe(double vitesse){
|
final SparkMax rotatione = new SparkMax(17, MotorType.kBrushless);
|
||||||
grimpeur.set(vitesse);
|
final DigitalInput limit3 = new DigitalInput(1);
|
||||||
|
|
||||||
|
public void balaye(double vitesse){
|
||||||
|
balaye.set(vitesse);
|
||||||
}
|
}
|
||||||
public boolean stop(){
|
public void rotationer(double vitesse){
|
||||||
return limit1.get();
|
rotatione.set(vitesse);
|
||||||
}
|
}
|
||||||
|
public boolean enHaut(){
|
||||||
|
return limit3.get();
|
||||||
|
}
|
||||||
public double encodeur(){
|
public double encodeur(){
|
||||||
return grimpeur.getEncoder().getPosition();
|
return rotatione.getEncoder().getPosition();
|
||||||
}
|
}
|
||||||
public void reset(){
|
public void reset(){
|
||||||
grimpeur.getEncoder().setPosition(0);
|
rotatione.getEncoder().setPosition(0);
|
||||||
}
|
}
|
||||||
|
public double amp(){
|
||||||
|
return balaye.getOutputCurrent();
|
||||||
|
}
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
// This method will be called once per scheduler run
|
// This method will be called once per scheduler run
|
Reference in New Issue
Block a user