Skip to content

Commit

Permalink
added pid things i think
Browse files Browse the repository at this point in the history
also erased errors
  • Loading branch information
samanthanguyen23 committed Dec 8, 2023
1 parent 31d3563 commit 4b349cd
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 23 deletions.
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/Commands/elevatorCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@

package frc.robot.commands;

import frc.robot.subsystems.ElevatorSubsystem;
// import frc.robot.subsystems.ElevatorSubsystem;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.ElevatorSubsystem;

/** An example command that uses an example subsystem. */
public class ElevatorCommand extends CommandBase {
Expand All @@ -18,23 +18,23 @@ public class ElevatorCommand extends CommandBase {
* @param subsystem The subsystem used by this command.
*/
double def;

public ElevatorCommand(ElevatorSubsystem elevatorSubsystem, double definition) {
this.elevatorSubsystem = elevatorSubsystem;
def = definition;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(elevatorSubsystem);
}

// 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() {

elevatorSubsystem.setTargetHeight(def);


elevatorSubsystem.setTargetHeight(def);
}

// Called once the command ends or is interrupted.
Expand All @@ -43,7 +43,7 @@ public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished(){
public boolean isFinished() {
return elevatorSubsystem.nearTargetHeight();
}
}
26 changes: 9 additions & 17 deletions src/main/java/frc/robot/Subsystems/ElevatorSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,14 @@
// the WPILib BSD license file in the root directory of this project.

package frc.robot.subsystems;

import com.ctre.phoenix.motorcontrol.TalonFXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonFX;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.Constants.Elevator;

// private PIDController controller;
Expand All @@ -26,17 +25,15 @@ public class ElevatorSubsystem extends SubsystemBase {
private double currentHeight = 0;
private final ShuffleboardTab ElevatorTab = Shuffleboard.getTab("Elevator");


/** Creates a new ElevatorSubsystem. */
public ElevatorSubsystem() {

leftMotor = new TalonFX(14);
rightMotor = new TalonFX(15);


leftMotor.configFactoryDefault();
rightMotor.configFactoryDefault();

rightMotor.clearStickyFaults();
leftMotor.clearStickyFaults();

Expand All @@ -56,41 +53,36 @@ public ElevatorSubsystem() {
currentHeight = 0;
}


public static double inchesToTicks(double height) {
return Elevator.CARRIAGE_RATIO
* (Elevator.ELEVATOR_SPROCKET_DIAMETER_INCHES * Math.PI)
* ((height / Elevator.FALCON_CPR) * Elevator.ELEVATOR_GEAR_RATIO);
}

public static double ticksToInches(double ticks) {
return Elevator.CARRIAGE_RATIO
* (Elevator.ELEVATOR_SPROCKET_DIAMETER_INCHES * Math.PI)
* ((ticks / Elevator.FALCON_CPR) * Elevator.ELEVATOR_GEAR_RATIO);
}
public void setTargetHeight(double targetHeight){

public void setTargetHeight(double targetHeight) {
this.targetHeight = targetHeight;
}




@Override
public void periodic() {
// This method will be called once per scheduler run
double ticks = leftMotor.getSelectedSensorPosition();
motorPower = controller.calculate(ticksToInches(ticks), targetHeight);
leftMotor.set(TalonFXControlMode.PercentOutput, MathUtil.clamp(motorPower, -0.2, 0.2));

currentHeight = ticksToInches(-leftMotor.getSelectedSensorPosition());
}



public boolean nearTargetHeight(){
if(targetHeight -0.5 <= currentHeight && currentHeight <= targetHeight +0.5){
public boolean nearTargetHeight() {
if (targetHeight - 0.5 <= currentHeight && currentHeight <= targetHeight + 0.5) {
return true;
}
return false;
}

}

0 comments on commit 4b349cd

Please sign in to comment.