Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
commit
fb2528a61d
@ -46,6 +46,7 @@ public class Constants {
|
||||
public static int guideurhaut = 23;
|
||||
public static int guideurbas = 24;
|
||||
public static int limitacc = 25;
|
||||
public static int limitacc2 = 76;
|
||||
public static int limithaut = 28;
|
||||
public static int limitbas = 29;
|
||||
|
||||
|
@ -4,12 +4,45 @@
|
||||
|
||||
package frc.robot;
|
||||
|
||||
import edu.wpi.first.cameraserver.CameraServer;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
|
||||
// Manette
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
|
||||
// Subsystem
|
||||
import frc.robot.subsystem.Accumulateur;
|
||||
import frc.robot.subsystem.Balayeuse;
|
||||
import frc.robot.subsystem.Drive;
|
||||
import frc.robot.subsystem.Grimpeur;
|
||||
import frc.robot.subsystem.Guideur;
|
||||
import frc.robot.subsystem.Lanceur;
|
||||
|
||||
|
||||
public class RobotContainer {
|
||||
|
||||
Drive drive = new Drive();
|
||||
Accumulateur accumulateur = new Accumulateur();
|
||||
Balayeuse balayeuse = new Balayeuse();
|
||||
Grimpeur grimpeur = new Grimpeur();
|
||||
Guideur guideur = new Guideur();
|
||||
Lanceur lanceur = new Lanceur();
|
||||
|
||||
CommandJoystick joystick = new CommandJoystick(0);
|
||||
CommandXboxController manette = new CommandXboxController(1);
|
||||
|
||||
public RobotContainer() {
|
||||
|
||||
CameraServer.startAutomaticCapture();
|
||||
|
||||
configureBindings();
|
||||
drive.setDefaultCommand(new RunCommand(()->{
|
||||
drive.drive(-MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(-joystick.getX(),0.2), MathUtil.applyDeadband(-joystick.getZ(), 0.2));
|
||||
},drive));
|
||||
}
|
||||
|
||||
private void configureBindings() {}
|
||||
|
@ -16,10 +16,12 @@ public class Accumulateur extends SubsystemBase {
|
||||
|
||||
final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2);
|
||||
final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc);
|
||||
final DigitalInput limitacc = new DigitalInput(0);
|
||||
final DigitalInput limitacc = new DigitalInput(Constants.limitacc);
|
||||
final DigitalInput limitacc2 = new DigitalInput(Constants.limitacc2);
|
||||
public void Deaccumuler(double vitesse){Moteuracc2.set(vitesse);}
|
||||
public void moteuraccfollow(){Moteuracc.follow(Moteuracc2); Moteuracc.setInverted(true);}
|
||||
|
||||
public boolean limitswitch1(){return limitacc.get();}
|
||||
public boolean limitswitch2(){return limitacc2.get();}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
|
Loading…
x
Reference in New Issue
Block a user