Skip to content

Commit

Permalink
Merge pull request #155 from 4201VitruvianBots/dev-climberFixes
Browse files Browse the repository at this point in the history
Fixed Climber Code
  • Loading branch information
jonathandao0 authored Mar 14, 2024
2 parents 5505d8e + 1f54e77 commit 939e8fc
Show file tree
Hide file tree
Showing 12 changed files with 144 additions and 131 deletions.
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -153,11 +153,9 @@ private void configureBindings() {
var driveShootButton = new Trigger(() -> leftJoystick.getRawButton(1));
driveShootButton.whileTrue(new AmpIntake(m_intake, 0.55, 0.75, m_ampShooter, 0.75));

// var aimNoteButton = new Trigger(() -> leftJoystick.getRawButton(1));
// aimNoteButton.whileTrue(new SetTrackingState(m_swerveDrive, TRACKING_STATE.NOTE));

var targetSpeakerButton = new Trigger(() -> rightJoystick.getRawButton(1));
targetSpeakerButton.whileTrue(new SetTrackingState(m_swerveDrive, TRACKING_STATE.SPEAKER));

// var targetNoteButton = new Trigger(() -> rightJoystick.getRawButton(2));
// targetNoteButton.whileTrue(new SetTrackingState(m_swerveDrive, TRACKING_STATE.NOTE));

Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/commands/arm/ArmJoystick.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@ public void execute() {
Units.degreesToRotations(ARM.maxAngleDegrees));
m_arm.setDesiredSetpointRotations(rotationSetpoint);
} else if (m_arm.getControlMode() == ROBOT.CONTROL_MODE.OPEN_LOOP) {
// if (ARM.limitOpenLoop) {
// // Upper limit
// if (m_arm.getCurrentAngle() >= ARM.maxAngleDegrees - 1)
// m_joystickDeadband = Math.min(m_joystickDeadband, 0);
Expand All @@ -53,8 +52,9 @@ public void execute() {
// if (m_arm.getCurrentAngle() <= ARM.minAngleDegrees + 1)
// m_joystickDeadband = Math.max(m_joystickDeadband, 0);
// }
// m_arm.setPercentOutput(m_joystickDeadband * ARM.joystickMultiplier);
m_arm.setFocOutput(m_joystickDeadband * ARM.joystickMultiplier);

m_arm.setPercentOutput(m_joystickDeadband * ARM.joystickMultiplier);
// m_arm.setFocOutput(m_joystickDeadband * ARM.joystickMultiplier);
}
} else {
m_arm.setPercentOutput(0.0);
Expand Down
32 changes: 14 additions & 18 deletions src/main/java/frc/robot/commands/climber/RunClimberJoystick.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

package frc.robot.commands.climber;

import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
Expand Down Expand Up @@ -41,22 +40,19 @@ public void execute() {
// Adds a Deadband so joystick Ys below 0.05 won't be registered
// This function was causing a lot of overruns!!!
// TODO: rewrite logic
double joystickYDeadbandOutput = MathUtil.applyDeadband(m_joystickY.getAsDouble(), 0.1);

if (m_climber.getClosedLoopControlMode() == CONTROL_MODE.OPEN_LOOP) {
double joystickYDeadbandOutput = MathUtil.applyDeadband(m_joystickY.getAsDouble(), 0.1);
// if (joystickYDeadbandOutput < 0)
// joystickYDeadbandOutput *= CLIMBER.kLimitedPercentOutputMultiplier;
m_climber.setJoystickY(joystickYDeadbandOutput);

if (joystickYDeadbandOutput != 0.0) {
// if (joystickYDeadbandOutput < 0)
// joystickYDeadbandOutput *= CLIMBER.kLimitedPercentOutputMultiplier;
m_climber.setJoystickY(joystickYDeadbandOutput);
m_climber.setClimbState(true);
}
if (joystickYDeadbandOutput == 0) {
m_climber.holdClimber();
m_climber.setPercentOutput(0);
}
} else {
m_climber.holdClimber();
m_climber.setClimberNeutralMode(NeutralModeValue.Brake);
if (joystickYDeadbandOutput == 0) m_climber.holdClimber();
} else if (m_climber.getClosedLoopControlMode() == CONTROL_MODE.CLOSED_LOOP) {
m_climber.setDesiredPositionMeters(
m_climber.getHeightMetersMotor1() + joystickYDeadbandOutput * 0.5);

if (joystickYDeadbandOutput == 0) m_climber.holdClimber();
}

if (m_climber.getAvgCurrentDraw() >= 30) {
Expand All @@ -69,9 +65,9 @@ public void execute() {
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_climber.holdClimber();
m_climber.setClimberNeutralMode(NeutralModeValue.Brake);
m_climber.setClimbState(false);
// m_climber.holdClimber();
// m_climber.setClimberNeutralMode(NeutralModeValue.Brake);
// m_climber.setClimbState(false);
}

// Returns true when the command should end.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ public void execute() {}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_climber.setDesiredSetpoint(CLIMBER.CLIMBER_SETPOINT.FULL_RETRACT.getSetpointMeters());
m_climber.setDesiredPositionMeters(CLIMBER.CLIMBER_SETPOINT.FULL_RETRACT.getSetpointMeters());
}

// Returns true when the command should end.
Expand Down
110 changes: 52 additions & 58 deletions src/main/java/frc/robot/commands/climber/ToggleClimbMode.java
Original file line number Diff line number Diff line change
@@ -1,58 +1,52 @@
// 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.climber;

import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.robot.constants.ROBOT;
import frc.robot.constants.ROBOT.CONTROL_MODE;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Climber;

public class ToggleClimbMode extends InstantCommand {
private final Climber m_climber;
private final Arm m_arm;

/** Creates a new ToggleClimberControlMode. */
public ToggleClimbMode(Climber climber, Arm arm) {
m_climber = climber;
m_arm = arm;

// Use addRequirements() here to declare subsystem dependencies.
addRequirements(m_climber, m_arm);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
// m_climber.setClimbState(!m_climber.getClimbState());
// m_arm.setControlMode(CONTROL_MODE.OPEN_LOOP);
ROBOT.CONTROL_MODE climberControlMode = m_climber.getClosedLoopControlMode();

switch (climberControlMode) {
case OPEN_LOOP:
m_climber.setClosedLoopControlMode(CONTROL_MODE.CLOSED_LOOP);
m_climber.resetMotionMagicState();
m_climber.holdClimber();
break;
default:
case CLOSED_LOOP:
m_climber.setClosedLoopControlMode(CONTROL_MODE.OPEN_LOOP);
break;
}
}

@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return true;
}
}
// 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.climber;

import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.robot.constants.ROBOT.CONTROL_MODE;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Climber;

public class ToggleClimbMode extends InstantCommand {
private final Climber m_climber;
private final Arm m_arm;

/** Creates a new ToggleClimberControlMode. */
public ToggleClimbMode(Climber climber, Arm arm) {
m_climber = climber;
m_arm = arm;

// Use addRequirements() here to declare subsystem dependencies.
addRequirements(m_climber, m_arm);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
// m_climber.setClimbState(!m_climber.getClimbState());
// m_arm.setControlMode(CONTROL_MODE.OPEN_LOOP);
var climbMode = m_climber.getClimbState();

if (!climbMode) {
m_climber.setClimbState(true);
// m_climber.setClosedLoopControlMode(CONTROL_MODE.CLOSED_LOOP);
// m_climber.resetMotionMagicState();
// m_climber.holdClimber();
m_arm.setControlMode(CONTROL_MODE.CLOSED_LOOP);
m_arm.resetMotionMagicState();
} else {
m_climber.setClimbState(false);
// m_climber.setClosedLoopControlMode(CONTROL_MODE.OPEN_LOOP);
m_arm.setControlMode(CONTROL_MODE.OPEN_LOOP);
}
}

@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
isClimbing = m_climber.getClimbState(); // TODO: Implement this in the climber command
isClimbing = m_climber.getClimbState();
isReved = m_shooter.getReved();
isUnreved = m_shooter.getUnreved(); // Done
isIntaked = m_intake.checkEitherIntakeSensorActive();
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/constants/ARM.java
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ public double get() {

public static final double mountingAngleDegrees = 0;

public static final double maxOutput = 1.0;
public static final double maxOutput = 0.6;

public static final double joystickMultiplier = maxOutput;

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/constants/CLIMBER.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ public final class CLIMBER {
public static final double kV = 0.0; // 12.57;
public static final double kA = 0.0; // 0.04;

public static final double kP = 100.0;
public static final double kP = 10.0;
public static final double kI = 0.00;
public static final double kD = 0.00;

Expand Down
8 changes: 7 additions & 1 deletion src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand Down Expand Up @@ -100,6 +101,11 @@ public Arm() {
config.MotorOutput.PeakForwardDutyCycle = ARM.maxOutput;
config.MotorOutput.PeakReverseDutyCycle = -ARM.maxOutput;

// Ramp rates for climbing
config.OpenLoopRamps.DutyCycleOpenLoopRampPeriod = 2.0;
config.OpenLoopRamps.TorqueOpenLoopRampPeriod = 2.0;
config.OpenLoopRamps.VoltageOpenLoopRampPeriod = 2.0;

config.MotionMagic.MotionMagicAcceleration = ARM.kAccel;
config.MotionMagic.MotionMagicCruiseVelocity = ARM.kCruiseVel;
config.MotionMagic.MotionMagicJerk = ARM.kJerk;
Expand All @@ -111,7 +117,7 @@ public Arm() {
canCoderConfig.MagnetSensor.MagnetOffset = ARM.canCoderOffset;
CtreUtils.configureCANCoder(m_armEncoder, canCoderConfig);

m_armEncoder.setPosition(m_armEncoder.getPosition().getValue());
if (RobotBase.isReal()) m_armEncoder.setPosition(m_armEncoder.getPosition().getValue());

SmartDashboard.putData(this);
}
Expand Down
Loading

0 comments on commit 939e8fc

Please sign in to comment.