Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 @@ -31,6 +31,12 @@ public static class CAN {
public static final int Victor4 = 4;
public static final int Talon5 = 5;
public static final int Falcon = 14;
public static final int climberMotor = -1;
}

public static class IDs{
public static final int climberLimitHome = -1;
public static final int climberLimitExtended = -1;
}

public static class Swerve {
Expand Down
43 changes: 43 additions & 0 deletions src/main/java/frc/robot/commands/Climb.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
// 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.

package frc.robot.commands;

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

/** An example command that uses an example subsystem. */
public class Climb extends Command {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final Climber climber;

public Climb(ExampleSubsystem subsystem) {
climber = new Climber();
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(climber);
}

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

// 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) {
climber.stopMoving();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return climber.isHome();
}
}
41 changes: 41 additions & 0 deletions src/main/java/frc/robot/commands/ExtendClimber.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// 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.

package frc.robot.commands;

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

public class ExtendClimber extends Command {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final Climber climber;

public ExtendClimber(ExampleSubsystem subsystem) {
climber = new Climber();
addRequirements(climber);
}

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

// 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) {
climber.stopMoving();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return climber.isExtended();
}
}
43 changes: 43 additions & 0 deletions src/main/java/frc/robot/subsystems/Climber.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
// 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.

package frc.robot.subsystems;

import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class Climber extends SubsystemBase {
private final TalonFX climberMotor;
private final DigitalInput limitHome;
private final DigitalInput limitExtended;
private final double climbSpeed = .1;

public Climber() {
climberMotor = new TalonFX(Constants.CAN.climberMotor, "rio");
limitHome = new DigitalInput(Constants.IDs.climberLimitHome);
limitExtended = new DigitalInput(Constants.IDs.climberLimitExtended);
climberMotor.getConfigurator().apply(new TalonFXConfiguration());
}
public void stopMoving() {
climberMotor.set(0);
}
public void extend() {
climberMotor.set(climbSpeed);
}
public boolean isExtended() {
return limitExtended.get();
}
public void goHome(){climberMotor.set(-climbSpeed);}
public boolean isHome() {
return limitHome.get();
}
public boolean exampleCondition() {
// Query some boolean state, such as a digital sensor.
return false;
}
}