Skip to content

Commit

Permalink
New Branch for Potentiometers, do not use as voltage information stil…
Browse files Browse the repository at this point in the history
…l needs to be found
  • Loading branch information
ProgrammingSR committed Mar 16, 2024
1 parent 841b71d commit 8908f8b
Show file tree
Hide file tree
Showing 3 changed files with 54 additions and 2 deletions.
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -156,5 +156,15 @@ public static final class VisionConstants {
public static final double kFieldWidth = 8.21055;
public static final double kFieldLength = 16.54175;
}
public static final class AutonConstants{
public static final int kAnalogInputPortLoc = 0;
public static final int kAnalogInputPortPath = 1;
public static final int kPotentiometerFullRange = 180;
public static final int kPotentiometerOffset = 30;
public static final double kLocMaxVoltage = 5;
public static final double kPathMaxVoltage = 5;
}
}



}
16 changes: 15 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
Expand All @@ -26,6 +28,7 @@
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants.AutonConstants;
import frc.robot.Constants.DriveConstants;
import frc.robot.Constants.IOConstants;
import frc.robot.Constants.ShooterConstants;
Expand All @@ -36,6 +39,7 @@
import frc.robot.subsystems.ClimberSubsystem;
import frc.robot.subsystems.DriveSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.PotentiometerSubsystem;
import frc.robot.subsystems.IntakeSubsystem.ArmPosition;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.ShooterSubsystem.ShootSpeed;
Expand All @@ -57,9 +61,13 @@ public class RobotContainer {

private final XboxController m_driverController = new XboxController(IOConstants.kDriverControllerPort);
private final XboxController m_operatorController = new XboxController(IOConstants.kOperatorControllerPort);

private final PotentiometerSubsystem m_PotentiometerSubsystem = new PotentiometerSubsystem();
private final SendableChooser<Command> autoChooser;

// Potentiometere



/**
* The container for the robot. Contains subsystems, IO devices, and commands.
*/
Expand Down Expand Up @@ -115,7 +123,13 @@ public RobotContainer() {
m_visionSubsystem.addConsumer(m_robotDrive::addVisionMeasurement);

autoChooser = AutoBuilder.buildAutoChooser();
String pathPosition;
SmartDashboard.putData("Auto Chooser", autoChooser);






// Configure the trigger bindings
configureBindings();
Expand Down
28 changes: 28 additions & 0 deletions src/main/java/frc/robot/subsystems/PotentiometerSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.Constants.AutonConstants;

public class PotentiometerSubsystem {

private final AnalogPotentiometer LocationPotentiometer = new AnalogPotentiometer(AutonConstants.kAnalogInputPortLoc, AutonConstants.kPotentiometerFullRange, AutonConstants.kPotentiometerOffset);
private final AnalogPotentiometer PathPotentiometer = new AnalogPotentiometer(AutonConstants.kAnalogInputPortPath, AutonConstants.kPotentiometerFullRange, AutonConstants.kPotentiometerOffset);

public void periodic() {
double locationVoltage = LocationPotentiometer.get();
double pathVoltage = PathPotentiometer.get();
SmartDashboard.putNumber("Location Potentiometer", locationVoltage);
SmartDashboard.putNumber("Path Potentiometer", pathVoltage);
}
//TODO: Get values for voltages on the potentiometers so that when the voltage is in x-range or equal to x
//TODO: It will return y-path. right now num is undefined beucase the range is unknown.
public void getPath(double locationVoltage, double pathVoltage){
double num;
String path;
//if (pathVoltage < num){
//path = "1-Left-Leave-Delayed-6s";
//}
}
}

0 comments on commit 8908f8b

Please sign in to comment.