Skip to content

Commit c5d41c8

Browse files
feat: elevator (#7)
* feat: elevator * feat: d-pad bindings * minor fixes * temporarily disabled elevator subsystem * minor fixes again
1 parent 0277306 commit c5d41c8

File tree

3 files changed

+139
-0
lines changed

3 files changed

+139
-0
lines changed

src/main/java/frc/robot/Constants.java

+29
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,15 @@ public final class Constants {
3434
*/
3535
public static final class IOConstants {
3636
public static final int kDriverControllerPort = 0;
37+
public static final int kOperatorControllerPort = 1;
3738

3839
public static final double kControllerDeadband = 0.15;
3940
public static final double kSlowModeScalar = 0.8;
41+
42+
public static final int kDPadUp = 0;
43+
public static final int kDPadRight = 90;
44+
public static final int kDPadDown = 180;
45+
public static final int kDPadLeft = 270;
4046
}
4147

4248
public static final class DriveConstants {
@@ -113,4 +119,27 @@ public static final class VisionConstants {
113119
public static final boolean kUseVision = true;
114120
}
115121

122+
public static final class ElevatorConstants {
123+
// TODO: Set motor and distance sensor ports
124+
public static final int kElevatorMotorPort = 0;
125+
public static final int kElevatorCANrangePort = 0;
126+
127+
// TODO: Tune PID for elevator
128+
public static final double kPElevator = 0.03;
129+
130+
// TODO: Set these constants
131+
public static final double kElevatorGearing = 1;
132+
public static final double kElevatorMaxSpeed = 0.7;
133+
public static final double kElevatorFeedForward = 0.1;
134+
public static final double kElevatorSpeedScalar = 1;
135+
public static final double kElevatorBottom = 0;
136+
public static final double kElevatorTop = 1;
137+
public static final double kElevatorDistanceThreshold = 1;
138+
139+
public static final double kL1Height = 0.3;
140+
public static final double kL2Height = 0.5;
141+
public static final double kL3Height = 0.7;
142+
public static final double kL4Height = 0.9;
143+
}
144+
116145
}

src/main/java/frc/robot/RobotContainer.java

+37
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,12 @@
1212
import edu.wpi.first.wpilibj2.command.InstantCommand;
1313
import edu.wpi.first.wpilibj2.command.RunCommand;
1414
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
15+
import edu.wpi.first.wpilibj2.command.button.POVButton;
1516
import frc.robot.Constants.DriveConstants;
17+
import frc.robot.Constants.ElevatorConstants;
1618
import frc.robot.Constants.IOConstants;
1719
import frc.robot.subsystems.DriveSubsystem;
20+
import frc.robot.subsystems.ElevatorSubsystem;
1821

1922
/*
2023
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -25,8 +28,10 @@
2528
public class RobotContainer {
2629
// The robot's subsystems and commands are defined here
2730
private final DriveSubsystem m_robotDrive = new DriveSubsystem();
31+
// private final ElevatorSubsystem m_elevator = new ElevatorSubsystem(); // Temporarily commented out to merge
2832

2933
private final XboxController m_driverController = new XboxController(IOConstants.kDriverControllerPort);
34+
private final XboxController m_operatorController = new XboxController(IOConstants.kOperatorControllerPort);
3035

3136
/**
3237
* The container for the robot. Contains subsystems, OI devices, and commands.
@@ -64,17 +69,48 @@ public RobotContainer() {
6469
* -1,
6570
!m_driverController.getRightBumperButton()),
6671
m_robotDrive));
72+
73+
/* Temporarily commented out to merge
74+
m_elevator.setDefaultCommand(
75+
new RunCommand(
76+
() -> m_elevator.trackPosition(
77+
MathUtil.applyDeadband(
78+
-m_operatorController.getLeftY(),
79+
IOConstants.kControllerDeadband)),
80+
m_elevator));
81+
*/
82+
6783
}
6884

6985
/**
7086
* Use this method to define your button->command mappings.
7187
*/
7288
private void configureBindings() {
89+
7390
new JoystickButton(m_driverController, Button.kStart.value)
7491
.onTrue(new InstantCommand(m_robotDrive::zeroHeading, m_robotDrive));
7592

7693
new JoystickButton(m_driverController, Button.kBack.value)
7794
.onTrue(new InstantCommand(() -> {m_robotDrive.resetOdometry(new Pose2d());}, m_robotDrive));
95+
96+
/* Temporarily commented out to merge
97+
new POVButton(m_operatorController, ElevatorConstants.kDPadUp) // Up - L1
98+
.onTrue(new InstantCommand(
99+
() -> m_elevator.setHeight(ElevatorConstants.kL1Height)
100+
));
101+
new POVButton(m_operatorController, ElevatorConstants.kDPadRight) // Right - L2
102+
.onTrue(new InstantCommand(
103+
() -> m_elevator.setHeight(ElevatorConstants.kL2Height)
104+
));
105+
new POVButton(m_operatorController, ElevatorConstants.kDPadDown) // Down - L3
106+
.onTrue(new InstantCommand(
107+
() -> m_elevator.setHeight(ElevatorConstants.kL3Height)
108+
));
109+
new POVButton(m_operatorController, ElevatorConstants.kDPadLeft) // Left - L4
110+
.onTrue(new InstantCommand(
111+
() -> m_elevator.setHeight(ElevatorConstants.kL4Height)
112+
));
113+
*/
78114
}
79115

80116
/**
@@ -97,5 +133,6 @@ public Command getAutonomousCommand() {
97133
*/
98134
public void fastPeriodic() {
99135
m_robotDrive.fastPeriodic();
136+
//m_elevator.fastPeriodic(); // Temporarily commented out to merge
100137
}
101138
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
// Copyright (c) FIRST and other WPILib contributors.
2+
// Open Source Software; you can modify and/or share it under the terms of
3+
// the WPILib BSD license file in the root directory of this project.
4+
5+
package frc.robot.subsystems;
6+
7+
import com.ctre.phoenix6.hardware.CANrange;
8+
import com.revrobotics.spark.SparkFlex;
9+
import com.revrobotics.spark.SparkBase.PersistMode;
10+
import com.revrobotics.spark.SparkBase.ResetMode;
11+
import com.revrobotics.spark.SparkLowLevel.MotorType;
12+
import com.revrobotics.spark.config.SparkFlexConfig;
13+
14+
import edu.wpi.first.math.MathUtil;
15+
import edu.wpi.first.math.controller.PIDController;
16+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
17+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
18+
import frc.robot.Constants;
19+
import frc.robot.Robot;
20+
import frc.robot.Constants.ElevatorConstants;
21+
22+
public class ElevatorSubsystem extends SubsystemBase {
23+
private final SparkFlex m_elevatorMotor;
24+
private final CANrange m_elevatorRange = new CANrange(ElevatorConstants.kElevatorCANrangePort);
25+
26+
private final PIDController m_PIDController = new PIDController(ElevatorConstants.kPElevator, 0, 0, Constants.kFastPeriodicPeriod);
27+
28+
private double m_targetPosition = 0;
29+
private double m_motorOffset = 0;
30+
31+
/** Creates a new ElevatorSubsystem. */
32+
public ElevatorSubsystem() {
33+
SparkFlexConfig motorConfig = new SparkFlexConfig();
34+
motorConfig.encoder.positionConversionFactor(ElevatorConstants.kElevatorGearing);
35+
36+
m_elevatorMotor = new SparkFlex(ElevatorConstants.kElevatorMotorPort, MotorType.kBrushless);
37+
// TODO: set to reset and persist after testing
38+
m_elevatorMotor.configure(motorConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
39+
}
40+
41+
@Override
42+
public void periodic() {
43+
// This method will be called once per scheduler run
44+
if (m_elevatorRange.getDistance().getValueAsDouble() < ElevatorConstants.kElevatorDistanceThreshold) {
45+
// This offset is set when the distance sensor detects that the elevator is at the bottom
46+
// At the bottom, the motor's position + offset should equal 0
47+
m_motorOffset = -m_elevatorMotor.getEncoder().getPosition();
48+
}
49+
}
50+
51+
public void fastPeriodic() {
52+
double output = m_PIDController.calculate(
53+
m_elevatorMotor.getEncoder().getPosition() + m_motorOffset,
54+
m_targetPosition) + ElevatorConstants.kElevatorFeedForward;
55+
output = MathUtil.clamp(output, -ElevatorConstants.kElevatorMaxSpeed, ElevatorConstants.kElevatorMaxSpeed);
56+
m_elevatorMotor.set(output);
57+
58+
SmartDashboard.putNumber("elevator motor output", output);
59+
}
60+
61+
public void trackPosition(double leftY) {
62+
// Moves the target position by leftY multiplied by the constant kSpeed, clamped between the top and bottom heights
63+
m_targetPosition += leftY * ElevatorConstants.kElevatorSpeedScalar * Robot.kDefaultPeriod;
64+
m_targetPosition = MathUtil.clamp(m_targetPosition, ElevatorConstants.kElevatorBottom, ElevatorConstants.kElevatorTop);
65+
// Display this number for now so we can see it
66+
SmartDashboard.putNumber("elevator targetPosition", m_targetPosition);
67+
}
68+
69+
public void setHeight(double level) {
70+
// Set the elevator target height to the corresponding level (L1, L2, L3, L4)
71+
m_targetPosition = level;
72+
}
73+
}

0 commit comments

Comments
 (0)