camera
This commit is contained in:
parent
92325aebca
commit
56d9774135
@ -3,6 +3,7 @@
|
|||||||
// the WPILib BSD license file in the root directory of this project.
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
package frc.robot;
|
package frc.robot;
|
||||||
|
import edu.wpi.first.cameraserver.CameraServer;
|
||||||
import edu.wpi.first.math.MathUtil;
|
import edu.wpi.first.math.MathUtil;
|
||||||
import edu.wpi.first.networktables.GenericEntry;
|
import edu.wpi.first.networktables.GenericEntry;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
|
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
|
||||||
@ -32,8 +33,6 @@ public class RobotContainer {
|
|||||||
Lanceur lanceur = new Lanceur();
|
Lanceur lanceur = new Lanceur();
|
||||||
Accumulateur accumulateur = new Accumulateur();
|
Accumulateur accumulateur = new Accumulateur();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
ShuffleboardTab dashboard = Shuffleboard.getTab("Dashboard");
|
ShuffleboardTab dashboard = Shuffleboard.getTab("Dashboard");
|
||||||
ShuffleboardLayout forces = Shuffleboard.getTab("Dashboard")
|
ShuffleboardLayout forces = Shuffleboard.getTab("Dashboard")
|
||||||
.getLayout("forces", BuiltInLayouts.kList)
|
.getLayout("forces", BuiltInLayouts.kList)
|
||||||
@ -50,7 +49,7 @@ public class RobotContainer {
|
|||||||
CommandJoystick joystick1 = new CommandJoystick(0);
|
CommandJoystick joystick1 = new CommandJoystick(0);
|
||||||
Drive drive = new Drive();
|
Drive drive = new Drive();
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
|
CameraServer.startAutomaticCapture();
|
||||||
configureBindings();
|
configureBindings();
|
||||||
drive.setDefaultCommand(new RunCommand(()->{
|
drive.setDefaultCommand(new RunCommand(()->{
|
||||||
drive.drive(-joystick1.getY(), -joystick1.getX(), MathUtil.applyDeadband(-joystick1.getZ(), 0.2));
|
drive.drive(-joystick1.getY(), -joystick1.getX(), MathUtil.applyDeadband(-joystick1.getZ(), 0.2));
|
||||||
|
@ -22,6 +22,7 @@ public class Drive extends SubsystemBase {
|
|||||||
swerveDrive.drive(new Translation2d(x, y), zRotation, false, false);
|
swerveDrive.drive(new Translation2d(x, y), zRotation, false, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/** Creates a new Drive. */
|
/** Creates a new Drive. */
|
||||||
public Drive() {
|
public Drive() {
|
||||||
@ -31,7 +32,8 @@ public class Drive extends SubsystemBase {
|
|||||||
e.printStackTrace();
|
e.printStackTrace();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
public SwerveModulePosition[] distance(){
|
|
||||||
|
public SwerveModulePosition[] distance(){
|
||||||
return swerveDrive.getModulePositions();
|
return swerveDrive.getModulePositions();
|
||||||
}
|
}
|
||||||
@Override
|
@Override
|
||||||
|
Loading…
x
Reference in New Issue
Block a user