Skip to content

Commit

Permalink
switch to new launch motor
Browse files Browse the repository at this point in the history
  • Loading branch information
robo7660 committed Feb 29, 2024
1 parent 900497e commit d2412ba
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 2 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,7 @@ public void teleopInit() {
}
getAlliance();
m_robotContainer.updatePose();
m_robotContainer.dropLauncher();
}

/** This function is called periodically during operator control. */
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -155,4 +155,8 @@ public void setMotorBrake(boolean brake) {
public void updatePose() {
m_swerve.updatePositionCommand();
}

public void dropLauncher(){
m_launch.releaseLauncher();
}
}
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/subsystems/Launcher.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ public class Launcher extends SubsystemBase {
private RelativeEncoder upperLauncherEncoder;
private RelativeEncoder lowerLauncherEncoder;

private CANSparkMax angle = new CANSparkMax(Constants.Launch.angleID, MotorType.kBrushless);
private CANSparkFlex angle = new CANSparkFlex(Constants.Launch.angleID, MotorType.kBrushless);
private SparkPIDController angleController;
private SparkAbsoluteEncoder angleEncoder;

Expand All @@ -46,7 +46,7 @@ public Launcher() {
angle.setInverted(Constants.Launch.angleMotorInverted);
upperLauncher.setInverted(Constants.Launch.upperMotorInverted);
lowerLauncher.setInverted(Constants.Launch.lowerMotorInverted);
angle.setIdleMode(IdleMode.kCoast);
angle.setIdleMode(IdleMode.kBrake);

angleController = angle.getPIDController();
upperLauncherController = upperLauncher.getPIDController();
Expand Down Expand Up @@ -207,6 +207,10 @@ public void periodic() {
SmartDashboard.putNumber("Angle Position", angleEncoder.getPosition());
}

public void releaseLauncher(){
angle.setIdleMode(IdleMode.kCoast);
}

public Command switchAngleCommand() {
return this.runOnce(() -> switchAngle());
}
Expand Down

0 comments on commit d2412ba

Please sign in to comment.