Skip to content

Commit

Permalink
changed shooter start positio
Browse files Browse the repository at this point in the history
  • Loading branch information
cherriae committed Mar 14, 2024
1 parent c9c691a commit 9152032
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 4 deletions.
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
package frc.robot;

import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.net.PortForwarder;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -35,6 +36,10 @@ 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();

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

TalonFXConfig.configureFalcon(_angleMotor, true);

_angleMotor.setPosition(67 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360);

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

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

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

_angleMotor.getConfigurator().apply(softLimits);

Expand Down Expand Up @@ -104,6 +105,7 @@ public double getVelocity() {
*/
public void driveAngle(double speed) {
_angleMotor.set(UtilFuncs.FromVolts(_angleFeed.calculate(Math.toRadians(getAngle()), 0)) + speed);
// _angleMotor.set(speed);
}

/** Stops the shooter's angular movement. */
Expand Down

0 comments on commit 9152032

Please sign in to comment.