Skip to content

Commit

Permalink
webcam
Browse files Browse the repository at this point in the history
  • Loading branch information
cherriae committed Mar 14, 2024
1 parent 9152032 commit d490dc3
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 9 deletions.
13 changes: 8 additions & 5 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,14 @@ public void robotInit() {
// FIRST THING THAT HAPPENS
addPeriodic(() -> AllianceHelper.getInstance().updateAlliance(DriverStation.getAlliance()), 0.5);

for (int port = 5800; port <= 5807; port++) {
PortForwarder.add(port, "limelight.local", port);
}

// CameraServer.startAutomaticCapture();
// for (int port = 5800; port <= 5807; port++) {
// PortForwarder.add(port, "limelight.local", port);
// }
PortForwarder.add(5800, "limelight.local", 5800);
PortForwarder.add(5801, "limelight.local", 5801);
PortForwarder.add(5805, "limelight.local", 5805);

CameraServer.startAutomaticCapture(0);

// Instantiate our RobotContainer. This will perform all our button bindings,
// and put our
Expand Down
9 changes: 5 additions & 4 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -50,16 +50,17 @@ public ShooterSubsystem() {
NeoConfig.configureFollowerNeo(_rightMotor, _leftMotor, true);

TalonFXConfig.configureFalcon(_angleMotor, true);
_angleMotor.setPosition(67 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360);
_angleMotor.setPosition(69 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360);
// _angleMotor.setPosition(0);

// soft limits
SoftwareLimitSwitchConfigs softLimits = new SoftwareLimitSwitchConfigs();

softLimits.ForwardSoftLimitThreshold = 67 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;
softLimits.ForwardSoftLimitThreshold = 69 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;
softLimits.ReverseSoftLimitThreshold = -25 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;

softLimits.ForwardSoftLimitEnable = true;
softLimits.ReverseSoftLimitEnable = true;
softLimits.ForwardSoftLimitEnable = false;
softLimits.ReverseSoftLimitEnable = false;

_angleMotor.getConfigurator().apply(softLimits);

Expand Down

0 comments on commit d490dc3

Please sign in to comment.