mode auto + modif
This commit is contained in:
parent
c28530ea50
commit
09e7f3f44c
@ -11,11 +11,13 @@ import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
|||||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import edu.wpi.first.wpilibj2.command.Commands;
|
||||||
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
||||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||||
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
|
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
|
||||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||||
|
import frc.robot.commands.AccAuto;
|
||||||
import frc.robot.commands.Avancer;
|
import frc.robot.commands.Avancer;
|
||||||
import frc.robot.commands.Force1;
|
import frc.robot.commands.Force1;
|
||||||
//import frc.robot.commands.Lancer;
|
//import frc.robot.commands.Lancer;
|
||||||
@ -25,6 +27,7 @@ import frc.robot.commands.Force4;
|
|||||||
import frc.robot.commands.Force5;
|
import frc.robot.commands.Force5;
|
||||||
import frc.robot.commands.Force6;
|
import frc.robot.commands.Force6;
|
||||||
import frc.robot.commands.Force7;
|
import frc.robot.commands.Force7;
|
||||||
|
import frc.robot.commands.LanceurAuto;
|
||||||
import frc.robot.commands.Force1;
|
import frc.robot.commands.Force1;
|
||||||
import frc.robot.commands.Reculer;
|
import frc.robot.commands.Reculer;
|
||||||
import frc.robot.commands.accumulateurtest;
|
import frc.robot.commands.accumulateurtest;
|
||||||
@ -35,7 +38,8 @@ import frc.robot.subsystems.Lanceur;
|
|||||||
public class RobotContainer {
|
public class RobotContainer {
|
||||||
Lanceur lanceur = new Lanceur();
|
Lanceur lanceur = new Lanceur();
|
||||||
Accumulateur accumulateur = new Accumulateur();
|
Accumulateur accumulateur = new Accumulateur();
|
||||||
|
Drive drive = new Drive();
|
||||||
|
Avancer avancer = new Avancer(drive);
|
||||||
|
|
||||||
|
|
||||||
ShuffleboardTab dashboard = Shuffleboard.getTab("Dashboard");
|
ShuffleboardTab dashboard = Shuffleboard.getTab("Dashboard");
|
||||||
@ -53,7 +57,6 @@ public class RobotContainer {
|
|||||||
|
|
||||||
CommandXboxController manette = new CommandXboxController(0);
|
CommandXboxController manette = new CommandXboxController(0);
|
||||||
CommandJoystick joystick1 = new CommandJoystick(0);
|
CommandJoystick joystick1 = new CommandJoystick(0);
|
||||||
Drive drive = new Drive();
|
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
|
|
||||||
configureBindings();
|
configureBindings();
|
||||||
@ -87,8 +90,10 @@ public class RobotContainer {
|
|||||||
|
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
return new SequentialCommandGroup(new ParallelCommandGroup(new Force1(lanceur).withTimeout(5),new accumulateurtest(accumulateur).withTimeout(5))
|
return Commands.deadline(Commands.waitSeconds(12)
|
||||||
,new Avancer(drive));
|
,new SequentialCommandGroup(new ParallelCommandGroup(new LanceurAuto(lanceur).withTimeout(6)
|
||||||
|
,new AccAuto(accumulateur).withTimeout(6))
|
||||||
|
)).andThen(avancer);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
41
src/main/java/frc/robot/commands/AccAuto.java
Normal file
41
src/main/java/frc/robot/commands/AccAuto.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.CommandBase;
|
||||||
|
import frc.robot.subsystems.Accumulateur;
|
||||||
|
|
||||||
|
public class AccAuto extends CommandBase {
|
||||||
|
private Accumulateur accumulateur;
|
||||||
|
/** Creates a new AccAuto. */
|
||||||
|
public AccAuto(Accumulateur accumulateur) {
|
||||||
|
this.accumulateur = accumulateur;
|
||||||
|
addRequirements(accumulateur);
|
||||||
|
// 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() {
|
||||||
|
accumulateur.reaccumuler();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
accumulateur.stop();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
@ -19,10 +19,10 @@ public class Avancer extends CommandBase {
|
|||||||
.withSize(3, 3);
|
.withSize(3, 3);
|
||||||
/** Creates a new Avancer. */
|
/** Creates a new Avancer. */
|
||||||
public Avancer(Drive drive) {
|
public Avancer(Drive drive) {
|
||||||
avancer.add("vitesse x", 1);
|
//avancer.add("vitesse x", 1);
|
||||||
avancer.add("vitesse y", 2);
|
// avancer.add("vitesse y", 2);
|
||||||
avancer.add("vitesse z", 3);
|
// avancer.add("vitesse z", 3);
|
||||||
avancer.add("distance", 4);
|
// avancer.add("distance", 4);
|
||||||
this.drive = drive;
|
this.drive = drive;
|
||||||
addRequirements(drive);
|
addRequirements(drive);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
@ -37,16 +37,18 @@ public class Avancer extends CommandBase {
|
|||||||
// 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() {
|
||||||
drive.drive(0.5, 0.2, 0);
|
drive.drive(0.5, -0.2, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// 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) {
|
||||||
|
drive.drive(0, 0, 0);
|
||||||
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return drive.distance()[0].distanceMeters>1;
|
return drive.distance()[0].distanceMeters>0.01;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -15,7 +15,7 @@ public class Force1 extends CommandBase {
|
|||||||
|
|
||||||
private Lanceur lanceur;
|
private Lanceur lanceur;
|
||||||
/** Creates a new LancerTest. */
|
/** Creates a new LancerTest. */
|
||||||
public Force1(Lanceur lanceur, g) {
|
public Force1(Lanceur lanceur, GenericEntry force1) {
|
||||||
dashboard.add("vitesse lanceur", 0.5);
|
dashboard.add("vitesse lanceur", 0.5);
|
||||||
this.lanceur = lanceur;
|
this.lanceur = lanceur;
|
||||||
addRequirements(lanceur);
|
addRequirements(lanceur);
|
||||||
|
@ -12,22 +12,26 @@ public class LanceurAuto extends CommandBase {
|
|||||||
/** Creates a new LanceurAuto. */
|
/** Creates a new LanceurAuto. */
|
||||||
public LanceurAuto(Lanceur lanceur) {
|
public LanceurAuto(Lanceur lanceur) {
|
||||||
this.lanceur = lanceur;
|
this.lanceur = lanceur;
|
||||||
|
addRequirements(lanceur);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {
|
public void initialize() {
|
||||||
lanceur.setPID(0, 0, 0);
|
lanceur.setPID(0.000000000000075572, 0, 0);}
|
||||||
}
|
|
||||||
|
|
||||||
// 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() {
|
||||||
|
lanceur.lancer(0.6);
|
||||||
|
}
|
||||||
|
|
||||||
// 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) {
|
||||||
|
lanceur.lancer(0);
|
||||||
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
|
Loading…
x
Reference in New Issue
Block a user