Skip to content

Commit

Permalink
climber updates
Browse files Browse the repository at this point in the history
  • Loading branch information
anorakthegreat committed Jan 17, 2025
1 parent 535c432 commit 3548b59
Show file tree
Hide file tree
Showing 6 changed files with 110 additions and 5 deletions.
42 changes: 42 additions & 0 deletions comp/src/main/java/org/team100/frc2024/Climber/Climber.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of

package org.team100.frc2024.Climber;

import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.TalonFXConfigurator;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;

import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Climber extends SubsystemBase {
/** Creates a new Climber. */

TalonFX climberMotor = new TalonFX(2);


CurrentLimitsConfigs currentConfigs = new CurrentLimitsConfigs();
TalonFXConfigurator talonFXConfigurator = climberMotor.getConfigurator();



public Climber() {
climberMotor.setNeutralMode(NeutralModeValue.Brake);
// currentConfigs.SupplyCurrentLimit = 10.0;
// currentConfigs.SupplyCurrentLimitEnable = true;
currentConfigs.StatorCurrentLimit = 50.0;
currentConfigs.StatorCurrentLimitEnable = true;
talonFXConfigurator.apply(currentConfigs);

}

public void setDutyCycle(double dutyCycle) {
climberMotor.set(dutyCycle);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}
}
49 changes: 49 additions & 0 deletions comp/src/main/java/org/team100/frc2024/Climber/ClimberRotate.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
// 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 org.team100.frc2024.Climber;

import java.util.function.Supplier;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj2.command.Command;

/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class ClimberRotate extends Command {
/** Creates a new ClimberRotate. */
Climber climber;
double duty;
Supplier<Double> m_joystick;

public ClimberRotate(Climber c, double d, Supplier<Double> joystick) {
// Use addRequirements() here to declare subsystem dependencies.
climber = c;
duty = d;
m_joystick = joystick;
addRequirements(climber);
}

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

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

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
climber.setDutyCycle(0);

}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
14 changes: 14 additions & 0 deletions comp/src/main/java/org/team100/frc2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
import java.util.Map;
import java.util.function.BooleanSupplier;

import org.team100.frc2024.Climber.Climber;
import org.team100.frc2024.Climber.ClimberRotate;
import org.team100.lib.async.Async;
import org.team100.lib.async.AsyncFactory;
import org.team100.lib.commands.drivetrain.DriveToPoseSimple;
Expand Down Expand Up @@ -80,7 +82,10 @@ public class RobotContainer implements Glassy {

private final SwerveModuleCollection m_modules;
// private final Command m_auton;

//SUBSYSTEMS
final SwerveDriveSubsystem m_drive;
final Climber m_climber;

public RobotContainer(TimedRobot100 robot) throws IOException {
final AsyncFactory asyncFactory = new AsyncFactory(robot);
Expand Down Expand Up @@ -147,6 +152,9 @@ public RobotContainer(TimedRobot100 robot) throws IOException {
swerveLocal,
visionDataProvider);


m_climber = new Climber();



///////////////////////////
Expand Down Expand Up @@ -208,6 +216,7 @@ public RobotContainer(TimedRobot100 robot) throws IOException {

// DEFAULT COMMANDS
m_drive.setDefaultCommand(driveManually);
m_climber.setDefaultCommand(new ClimberRotate(m_climber, 0.2, operatorControl::ramp));


//DRIVER BUTTONS
Expand All @@ -219,6 +228,11 @@ public RobotContainer(TimedRobot100 robot) throws IOException {
m_drive,
driveControllerFactory.fancyPIDF(PIDFlog),
swerveKinodynamics));


//OPERATOR BUTTONS
// whileTrue(operatorControl::ramp, new ClimberRotate(m_climber, 0.2 ));
// whileTrue(operatorControl::outtake, new ClimberRotate(m_climber, -0.2 ));



Expand Down
4 changes: 2 additions & 2 deletions lib/src/main/java/org/team100/lib/hid/OperatorControl.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ default boolean intake() {
return false;
}

default boolean ramp() {
return false;
default double ramp() {
return 0.0;
}

// this exists to bind to commands we don't want to run,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ public boolean feed() {
}

@Override
public boolean ramp() {
public double ramp() {
return m_operatorControl.ramp();
}

Expand Down
4 changes: 2 additions & 2 deletions lib/src/main/java/org/team100/lib/hid/OperatorV2Control.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ public boolean outtake() {
}

@Override
public boolean ramp() {
return m_controller.getAButton();
public double ramp() {
return m_controller.getRightY();
}

@Override
Expand Down

0 comments on commit 3548b59

Please sign in to comment.