Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Start camera command #153

Merged
merged 13 commits into from
Mar 20, 2024
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -230,4 +230,10 @@ public static class Climber {
/** Whether or not the climber is inverted. */
public static final boolean CLIMBER_INVERTED = true;
}

/** The constants for the USB cameras */
public static class Camera {
/** The camera id for the intake camera. */
public static final int INTAKE_CAMERA_ID = 0;
}
}
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@ public class Robot extends TimedRobot {
@Override
public void robotInit() {
robotContainer = new RobotContainer();

RobotContainer.startCamera.initialize();
}

@Override
Expand Down
12 changes: 7 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.robot.Controllers.ControllerAxis;
import frc.robot.Controllers.Keymap;
import frc.robot.commands.AimAndFireRoutine;
Expand All @@ -28,6 +27,7 @@
import frc.robot.commands.EnterXMode;
import frc.robot.commands.RunIntake;
import frc.robot.commands.RunIntakeReverse;
import frc.robot.commands.StartCamera;
import frc.robot.commands.auto.MoveAwayFromAmp;
import frc.robot.commands.auto.OnePieceAuto;
import frc.robot.commands.auto.TaxiAuto;
Expand Down Expand Up @@ -94,7 +94,7 @@ public class RobotContainer {
public static PDP pdp = new PDP();

/** Singleton instance of the intake {@link Camera} for the whole robot. */
public static Camera intakeCamera = new Camera(0);
public static Camera intakeCamera = new Camera(Constants.Camera.INTAKE_CAMERA_ID);

/*
* ************
Expand Down Expand Up @@ -219,6 +219,9 @@ public class RobotContainer {
/** Singleton instance of {@link ClimbDown} for the whole robot. */
public static ClimbDown climbDown = new ClimbDown();

/** Singleton instance of the intake {@link StartCamera} for the whole robot. */
public static StartCamera startIntakeCamera = new StartCamera(intakeCamera);

/* Autos */
/** Singleton instance of {@link MoveAwayFromAmp} for the whole robot. */
public static MoveAwayFromAmp moveAwayFromAmp = new MoveAwayFromAmp();
Expand All @@ -235,9 +238,6 @@ public class RobotContainer {
/** Singleton instance of {@link ZeroGyro} for the whole robot. */
public static ZeroGyro zeroGyro = new ZeroGyro();

public static InstantCommand startCamera =
new InstantCommand(intakeCamera::startCamera, intakeCamera);

/*
* ***********************
* * OTHER INSTANCE VARS *
Expand All @@ -256,6 +256,8 @@ public RobotContainer() {
Shuffleboard.getTab("Driver").add("Clear PDP sticky faults", clearPDPStickyFaults);
Shuffleboard.getTab("Driver").add("Zero Gyro", zeroGyro);

startIntakeCamera.schedule();

switch (Constants.Drive.currentDrivePerspective) {
case RobotOriented:
drive.setDefaultCommand(driveRobotOriented);
Expand Down
46 changes: 46 additions & 0 deletions src/main/java/frc/robot/commands/StartCamera.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// 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.

/*
* Asimov's Laws:
* The First Law: A robot may not injure a human being or, through inaction, allow a human being to come to harm.
* The Second Law: A robot must obey the orders given it by human beings except where such orders would conflict with the First Law.
* The Third Law: A robot must protect its own existence as long as such protection does not conflict with the First or Second Law.
*/

package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Camera;

/** Command that starts up a camera and sends it to shuffleboard. */
public class StartCamera extends Command {
private Camera camera;

/** Creates a new StartCamera. */
public StartCamera(Camera camera) {
this.camera = camera;
addRequirements(camera);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
camera.startCamera();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return true;
}
}
Loading