Skip to content

Commit

Permalink
Added conversion rates for encoders. :3
Browse files Browse the repository at this point in the history
Co-authored-by: Lapcas <Lapcas@users.noreply.github.com>
Co-authored-by: jopy-man <jopy-man@users.noreply.github.com>
Co-authored-by: Zixi52 <Zixi52@users.noreply.github.com>
Co-authored-by: naveed1117 <naveed1117@users.noreply.github.com>
  • Loading branch information
5 people committed Feb 16, 2024
1 parent bc9e9cd commit 8def4da
Show file tree
Hide file tree
Showing 4 changed files with 79 additions and 7 deletions.
1 change: 0 additions & 1 deletion src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ public class RobotContainer {
private final ConveyerTest conveyer = new ConveyerTest();
private final IntakeTest intake = new IntakeTest();


// Autons
private static SendableChooser<Command> autonChooser = new SendableChooser<>();

Expand Down
39 changes: 38 additions & 1 deletion src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,48 @@

import com.stuypulse.stuylib.network.SmartBoolean;
import com.stuypulse.stuylib.network.SmartNumber;
import edu.wpi.first.math.util.Units;

/*-
* File containing tunable settings for every subsystem on the robot.
*
* We use StuyLib's SmartNumber / SmartBoolean in order to have tunable
* values that we can edit on Shuffleboard.
*/
public interface Settings {}
public interface Settings {

public interface AmperTest {

double AMP_ROLLER_DIAMETER = Units.inchesToMeters(1.25);
public interface Lift{
public interface Encoder {
double GEARING = 9;
double DRUM_RADIUS = Units.inchesToMeters(1);
double DRUM_CIRCUMFERENCE = DRUM_RADIUS * Math.PI * 2;

double POSITION_CONVERSION = GEARING * DRUM_CIRCUMFERENCE;
double VELOCITY_CONVERSION = POSITION_CONVERSION / 60.0;
}
}
public interface Score {
SmartNumber SCORE_SPEED = new SmartNumber("Amper/Score/Score Speed", 1.0);
SmartNumber INTAKE_SPEED = new SmartNumber("Amper/Score/Intake Speed", 1.0);

double SCORE_MOTOR_CONVERSION = AMP_ROLLER_DIAMETER * Math.PI;
}

}

public interface ClimberTest {

public interface Encoder {
double GEAR_RATIO = 12.0;

double POSITION_CONVERSION = 1.0;
double VELOCITY_CONVERSION = POSITION_CONVERSION / 60.0;
}
}



}
21 changes: 20 additions & 1 deletion src/main/java/com/stuypulse/robot/subsystems/AmperTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.stuypulse.robot.constants.Ports;
import com.stuypulse.robot.constants.Settings;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
Expand All @@ -13,11 +14,20 @@ public class AmperTest extends SubsystemBase {
private final CANSparkMax scoreMotor;
private final CANSparkMax liftMotor;
private final RelativeEncoder liftEncoder;
private final RelativeEncoder scoreEncoder;



public AmperTest(){
scoreMotor = new CANSparkMax(Ports.Amper.SCORE, MotorType.kBrushless);
liftMotor = new CANSparkMax(Ports.Amper.LIFT, MotorType.kBrushless);
liftEncoder = liftMotor.getEncoder();
scoreEncoder = scoreMotor.getEncoder();

scoreEncoder.setPositionConversionFactor(Settings.AmperTest.Score.SCORE_MOTOR_CONVERSION);

liftEncoder.setPositionConversionFactor(Settings.AmperTest.Lift.Encoder.POSITION_CONVERSION);
liftEncoder.setVelocityConversionFactor(Settings.AmperTest.Lift.Encoder.VELOCITY_CONVERSION);
}

public void setAmperVoltage(double voltage){
Expand All @@ -32,7 +42,14 @@ public void stop(){
scoreMotor.set(0);
liftMotor.set(0);
}
public double getLiftEncoder() {

public double getScorePosition() {
return scoreEncoder.getPosition();
}
public double getLiftPosition() {
return liftEncoder.getPosition();
}
public double getLiftVelocity() {
return liftEncoder.getVelocity();
}
@Override
Expand All @@ -41,5 +58,7 @@ public void periodic() {
SmartDashboard.putNumber("Amper/Lift Speed", liftMotor.get());
SmartDashboard.putNumber("Amper/Intake Current", scoreMotor.getOutputCurrent());
SmartDashboard.putNumber("Amper/Lift Current", liftMotor.getOutputCurrent());
SmartDashboard.putNumber("Amper/Lift Position", liftEncoder.getPosition());
SmartDashboard.putNumber("Amper/Score Position", scoreEncoder.getPosition());
}
}
25 changes: 21 additions & 4 deletions src/main/java/com/stuypulse/robot/subsystems/ClimberTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.stuypulse.robot.constants.Ports;
import com.stuypulse.robot.constants.Settings;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
Expand All @@ -20,6 +21,13 @@ public ClimberTest(){

rightEncoder = rightMotor.getEncoder();
leftEncoder = leftMotor.getEncoder();

rightEncoder.setPositionConversionFactor(Settings.ClimberTest.Encoder.POSITION_CONVERSION);
leftEncoder.setPositionConversionFactor(Settings.ClimberTest.Encoder.POSITION_CONVERSION);

rightEncoder.setVelocityConversionFactor(Settings.ClimberTest.Encoder.VELOCITY_CONVERSION);
leftEncoder.setVelocityConversionFactor(Settings.ClimberTest.Encoder.VELOCITY_CONVERSION);

}
public void setLeftVoltage(double voltage){
leftMotor.set(voltage);
Expand All @@ -33,20 +41,29 @@ public void stop() {
rightMotor.set(0);
}

public double getLeftEncoder(){
public double getLeftVelocity() {
return leftEncoder.getVelocity();
}
public double getLeftPosition() {
return leftEncoder.getPosition();
}

public double getRightEncoder(){
public double getRightVelocity() {
return rightEncoder.getVelocity();
}

public double getRightPosition() {
return rightEncoder.getPosition();
}

@Override
public void periodic() {
SmartDashboard.putNumber("Climber/Left Voltage", leftMotor.getAppliedOutput() * leftMotor.getBusVoltage());
SmartDashboard.putNumber("Climber/Right Voltage", rightMotor.getAppliedOutput() * rightMotor.getBusVoltage());
SmartDashboard.putNumber("Climber/Height", getRightEncoder());
SmartDashboard.putNumber("Climber/Velocity", getLeftEncoder());
SmartDashboard.putNumber("Climber/Right Height", getRightPosition());
SmartDashboard.putNumber("Climber/Right Velocity", getRightVelocity());
SmartDashboard.putNumber("Climber/Left Position", getLeftPosition());
SmartDashboard.putNumber("Climber/Left Velocity", getLeftVelocity());
}
}

Expand Down

0 comments on commit 8def4da

Please sign in to comment.