Compare commits
No commits in common. "8afd6a74a515d94636021add7605f95116186978" and "0c36717d13b5d0966074680472debdbac8e1ca4f" have entirely different histories.
8afd6a74a5
...
0c36717d13
@ -49,8 +49,10 @@ import frc.robot.commands.requin.BalayeuseAlgue;
|
||||
import frc.robot.commands.requin.BalayeuseBas;
|
||||
import frc.robot.commands.requin.BalayeuseCoral;
|
||||
import frc.robot.commands.requin.BalayeuseHaut;
|
||||
import frc.robot.commands.requin.ExpireCorail;
|
||||
import frc.robot.commands.requin.ExpireAlgue;
|
||||
import frc.robot.commands.requin.L1Requin;
|
||||
import frc.robot.commands.requin.aspire;
|
||||
import frc.robot.commands.requin.exspire;
|
||||
import frc.robot.subsystems.Bougie;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Elevateur;
|
||||
@ -59,7 +61,6 @@ import frc.robot.subsystems.Limelight3;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
import frc.robot.subsystems.Pince;
|
||||
import frc.robot.subsystems.Requin;
|
||||
import frc.robot.commands.requin.exspire;
|
||||
|
||||
public class RobotContainer {
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed
|
||||
@ -122,9 +123,9 @@ public class RobotContainer {
|
||||
//pince
|
||||
manette1.rightTrigger().whileTrue(new CoralAlgueInspire(pince, bougie));
|
||||
manette1.rightBumper().whileTrue(new StationPince(pince, elevateur));
|
||||
manette1.leftTrigger().whileTrue(new AlgueExpire(pince, bougie));
|
||||
manette1.leftBumper().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY));
|
||||
manette1.povRight().whileTrue(new CoralExpire(pince, bougie));
|
||||
manette1.povRight().whileTrue(new AlgueExpire(pince, bougie));
|
||||
manette2.a().whileTrue(new CorailAspir(pince,bougie));
|
||||
manette2.b().whileTrue(new Algue_inspire(pince,bougie));
|
||||
//elevateur
|
||||
manette1.a().whileTrue(new Depart(elevateur, pince));
|
||||
manette1.b().whileTrue(new L2(elevateur,pince));
|
||||
@ -132,22 +133,15 @@ public class RobotContainer {
|
||||
manette1.y().whileTrue(new L4(elevateur, pince));
|
||||
|
||||
/* Manette 2 */
|
||||
manette2.a().whileTrue(new CorailAspir(pince,bougie));
|
||||
manette2.b().whileTrue(new Algue_inspire(pince,bougie));
|
||||
//requin
|
||||
manette2.rightBumper().whileTrue(new BalayeuseAlgue(requin,bougie));
|
||||
manette2.leftBumper().whileTrue(new L1Requin(requin, bougie));
|
||||
manette2.rightTrigger().whileTrue(new BalayeuseHaut(requin));
|
||||
manette1.leftTrigger().whileTrue(new exspire(requin, bougie));
|
||||
manette2.y().whileTrue(new BalayeuseAlgue(requin,bougie));
|
||||
manette2.x().whileTrue(new BalayeuseHaut(requin));
|
||||
manette2.rightTrigger().whileTrue(new ExpireAlgue(requin, bougie));
|
||||
manette2.leftTrigger().whileTrue(new BalayeuseCoral(requin, bougie));
|
||||
manette2.y().whileTrue(new exspire(requin, bougie));
|
||||
manette2.x().whileTrue(new ExpireCorail(requin, bougie));
|
||||
|
||||
|
||||
//grimpeur
|
||||
manette2.povDown().whileTrue(new GrimpeurManuelhaut(Grimpeur, bougie));
|
||||
manette2.povLeft().whileTrue(new GrimperHaut(Grimpeur, bougie));
|
||||
manette2.povRight().whileTrue(new GrimpeurBas(Grimpeur));
|
||||
//Pince manuel
|
||||
manette1.povUp().whileTrue(new L1Requin(requin, bougie));
|
||||
manette2.povUp().whileTrue(new aspire(requin, bougie));
|
||||
//Pince manuelle
|
||||
pince.setDefaultCommand(new RunCommand(()->{
|
||||
pince.pivote(MathUtil.applyDeadband(manette2.getRightY()*manette2.getRightY()*manette2.getRightY(), 0.05));
|
||||
}, pince));
|
||||
@ -158,9 +152,16 @@ public class RobotContainer {
|
||||
}, elevateur));
|
||||
|
||||
//limelight
|
||||
manette2.povUp().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
|
||||
manette2.leftBumper().whileTrue(new AprilTag3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
|
||||
manette2.rightBumper().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
|
||||
manette1.leftBumper().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY));
|
||||
|
||||
//Reset encodeur
|
||||
manette2.start().whileTrue(new reset(elevateur, pince));
|
||||
//grimpeur
|
||||
manette2.povDown().whileTrue(new GrimpeurManuelhaut(Grimpeur, bougie));
|
||||
manette2.povLeft().whileTrue(new GrimperHaut(Grimpeur, bougie));
|
||||
manette2.povRight().whileTrue(new GrimpeurBas(Grimpeur));
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
|
@ -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()>=670)
|
||||
if(requin.encodeur()<=715 && requin.encodeur()>=700)
|
||||
{
|
||||
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()>=1025){
|
||||
if(requin.encodeur()<=1200 && requin.encodeur()>=1050){
|
||||
requin.rotationer(0);
|
||||
if(requin.amp()>60){
|
||||
requin.balaye(0);
|
||||
|
@ -9,11 +9,12 @@ 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 ExpireCorail extends Command {
|
||||
public class ExpireAlgue extends Command {
|
||||
private Requin requin;
|
||||
private Bougie bougie;
|
||||
/** Creates a new ExpireAlgue. */
|
||||
public ExpireCorail(Requin requin, Bougie bougie) {
|
||||
public ExpireAlgue(Requin requin, Bougie bougie
|
||||
) {
|
||||
this.requin = requin;
|
||||
this.bougie = bougie;
|
||||
addRequirements(requin,bougie);
|
@ -30,6 +30,13 @@ 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);
|
||||
@ -37,6 +44,10 @@ public class L1Requin extends Command {
|
||||
else{
|
||||
requin.rotationer(0.5);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
51
src/main/java/frc/robot/commands/requin/aspire.java
Normal file
51
src/main/java/frc/robot/commands/requin/aspire.java
Normal file
@ -0,0 +1,51 @@
|
||||
// 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,7 +29,14 @@ public class exspire extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
requin.balaye(0.5);
|
||||
if(requin.amp()> 60){
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
else
|
||||
{
|
||||
bougie.Rouge();
|
||||
requin.balaye(0.5);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
Loading…
x
Reference in New Issue
Block a user