From 56d9774135bc0f1e7afaeb2b6f24c772067e1c37 Mon Sep 17 00:00:00 2001 From: Antoine PerreaultE Date: Tue, 5 Dec 2023 19:17:47 -0500 Subject: [PATCH] camera --- src/main/java/frc/robot/RobotContainer.java | 5 ++--- src/main/java/frc/robot/subsystems/Drive.java | 4 +++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 6e03240..b55a36e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -3,6 +3,7 @@ // the WPILib BSD license file in the root directory of this project. package frc.robot; +import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.math.MathUtil; import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; @@ -32,8 +33,6 @@ public class RobotContainer { Lanceur lanceur = new Lanceur(); Accumulateur accumulateur = new Accumulateur(); - - ShuffleboardTab dashboard = Shuffleboard.getTab("Dashboard"); ShuffleboardLayout forces = Shuffleboard.getTab("Dashboard") .getLayout("forces", BuiltInLayouts.kList) @@ -50,7 +49,7 @@ public class RobotContainer { CommandJoystick joystick1 = new CommandJoystick(0); Drive drive = new Drive(); public RobotContainer() { - + CameraServer.startAutomaticCapture(); configureBindings(); drive.setDefaultCommand(new RunCommand(()->{ drive.drive(-joystick1.getY(), -joystick1.getX(), MathUtil.applyDeadband(-joystick1.getZ(), 0.2)); diff --git a/src/main/java/frc/robot/subsystems/Drive.java b/src/main/java/frc/robot/subsystems/Drive.java index c0aa314..530646d 100644 --- a/src/main/java/frc/robot/subsystems/Drive.java +++ b/src/main/java/frc/robot/subsystems/Drive.java @@ -22,6 +22,7 @@ public class Drive extends SubsystemBase { swerveDrive.drive(new Translation2d(x, y), zRotation, false, false); } + /** Creates a new Drive. */ public Drive() { @@ -31,7 +32,8 @@ public class Drive extends SubsystemBase { e.printStackTrace(); } } - public SwerveModulePosition[] distance(){ + + public SwerveModulePosition[] distance(){ return swerveDrive.getModulePositions(); } @Override