touche
This commit is contained in:
@ -27,7 +27,7 @@ public class BalayeuseAlgue extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(requin.encodeur()<=715 && requin.encodeur()>=700)
|
||||
if(requin.encodeur()<=715 && requin.encodeur()>=670)
|
||||
{
|
||||
requin.rotationer(0);
|
||||
if(requin.amp()> 60){
|
||||
@ -40,10 +40,10 @@ public class BalayeuseAlgue extends Command {
|
||||
}
|
||||
}
|
||||
else if(requin.encodeur()>=700){
|
||||
requin.rotationer(0.5);
|
||||
requin.rotationer(-0.5);
|
||||
}
|
||||
else{
|
||||
requin.rotationer(-0.5);
|
||||
requin.rotationer(0.5);
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -27,7 +27,7 @@ public class BalayeuseCoral extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(requin.encodeur()<=1200 && requin.encodeur()>=1050){
|
||||
if(requin.encodeur()<=1200 && requin.encodeur()>=1025){
|
||||
requin.rotationer(0);
|
||||
if(requin.amp()>60){
|
||||
requin.balaye(0);
|
||||
|
@ -9,12 +9,11 @@ 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 ExpireAlgue extends Command {
|
||||
public class ExpireCorail extends Command {
|
||||
private Requin requin;
|
||||
private Bougie bougie;
|
||||
/** Creates a new ExpireAlgue. */
|
||||
public ExpireAlgue(Requin requin, Bougie bougie
|
||||
) {
|
||||
public ExpireCorail(Requin requin, Bougie bougie) {
|
||||
this.requin = requin;
|
||||
this.bougie = bougie;
|
||||
addRequirements(requin,bougie);
|
@ -30,13 +30,6 @@ public class L1Requin extends Command {
|
||||
|
||||
if(requin.encodeur()<=645 && requin.encodeur()>=600){
|
||||
requin.rotationer(0);
|
||||
if(requin.amp()>60){
|
||||
requin.balaye(-0.5);
|
||||
}
|
||||
else{
|
||||
requin.balaye(0);
|
||||
bougie.Rouge();
|
||||
}
|
||||
}
|
||||
else if(requin.encodeur()>=645){
|
||||
requin.rotationer(-0.5);
|
||||
@ -44,10 +37,6 @@ public class L1Requin extends Command {
|
||||
else{
|
||||
requin.rotationer(0.5);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -1,51 +0,0 @@
|
||||
// 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.requin;
|
||||
|
||||
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 aspire extends Command {
|
||||
/** Creates a new aspire. */
|
||||
private Requin requin;
|
||||
private Bougie bougie;
|
||||
public aspire(Requin requin, Bougie bougie) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
this.requin = requin;
|
||||
this.bougie = bougie;
|
||||
addRequirements(requin, bougie);
|
||||
}
|
||||
|
||||
// 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.amp()> 60){
|
||||
requin.balaye(0);
|
||||
bougie.Vert();
|
||||
}
|
||||
else
|
||||
{
|
||||
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;
|
||||
}
|
||||
}
|
@ -29,14 +29,7 @@ public class exspire extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(requin.amp()> 60){
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
else
|
||||
{
|
||||
bougie.Rouge();
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
Reference in New Issue
Block a user