Skip to content
This repository has been archived by the owner on Jan 2, 2025. It is now read-only.

Commit

Permalink
fix conversions
Browse files Browse the repository at this point in the history
  • Loading branch information
jack60612 committed Feb 27, 2024
1 parent b52816a commit a74f32a
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 5 deletions.
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,13 +53,13 @@ public static final class CANConstants {
// Analog Ports
/// Ultrasonic Sensors and ports.
public static final int ULTRASONICSHOOTERPORT = 0;
public static final int ARMLIMITSWITCHBACK = 1;
public static final int ARMLIMITSWITCHFRONT = 2;

// Digital Ports
public static final int ARMLIMITSWITCHBACK = 0;
public static final int ARMLIMITSWITCHFRONT = 1;

// Shooter Angles
public static final double ARMENCODEROFFSET = 0.8457221;
public static final double ARMENCODEROFFSET = 2.8378526;
public static final double ARMSTARTINGANGLE = 22.5; // WHY MaTH HURT
public static final double ARMMINRELATVESTART = 0.0;
public static final double ARMLOADANGLE = 65 - ARMSTARTINGANGLE;
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/subsystems/ArmSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,9 @@ public class ArmSubsystem extends SubsystemBase {
// gear ratio by dividing by the gear ratio.
// remember that 2pi radians in 360 degrees.
private final double kRadiansConversionRatio = (Math.PI * 2) / kGearRatio;
private final double kVelocityConversionRatio = kRadiansConversionRatio / 60;
private final double kAbsoluteRadiansConversionRatio = (Math.PI * 2);
private final double kAbsoluteVelocityConversionRatio = kAbsoluteRadiansConversionRatio / 60;
private final ArmFeedforward m_armFeedforward =
new ArmFeedforward(
ksArmVolts, kgArmGravityGain, kvArmVoltSecondsPerMeter, kaArmVoltSecondsSquaredPerMeter);
Expand Down Expand Up @@ -85,9 +87,11 @@ public ArmSubsystem(ShooterState shooterState) {
m_AbsoluteEncoder = m_armMotorMain.getAbsoluteEncoder();
m_AbsoluteEncoder.setInverted(false);
m_AbsoluteEncoder.setPositionConversionFactor(kAbsoluteRadiansConversionRatio);
m_AbsoluteEncoder.setVelocityConversionFactor(kAbsoluteVelocityConversionRatio);
// m_AbsoluteEncoder.setZeroOffset(Constants.ARMENCODEROFFSET);
// setup the encoders
m_MainEncoder.setPositionConversionFactor(kRadiansConversionRatio);
m_MainEncoder.setVelocityConversionFactor(kVelocityConversionRatio);
m_MainEncoder.setPosition(Units.degreesToRadians(Constants.ARMMINRELATVESTART));
// PID coefficients
kP = 1.7496;
Expand All @@ -104,6 +108,8 @@ public ArmSubsystem(ShooterState shooterState) {
m_armMainPIDController.setIZone(kIz);
m_armMainPIDController.setOutputRange(kMinOutput, kMaxOutput);
m_armMainPIDController.setFeedbackDevice(m_AbsoluteEncoder);
// m_armMotorMain.setSoftLimit(SoftLimitDirection.kReverse, kMinArmAngleRadians));
// m_armMotorMain.setSoftLimit(SoftLimitDirection.kForward, kMaxArmAngleRadians);
m_armMotorMain.burnFlash();

// setup SysID for auto profiling
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.Constants.CANConstants;
import frc.robot.Constants;
import frc.robot.Constants.CANConstants;
import frc.robot.DriveConstants;

/** This Subsystem is what allows the code to interact with the drivetrain of the robot. */
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ public class ShooterSubsystem extends SubsystemBase {
private final double kGearRatio = 4; // TBD
// basically converted from rotations to to radians to then meters using the wheel diameter.
// the diameter is already *2 so we don't need to multiply by 2 again.
private final double kVelocityConversionRatio = (Math.PI * kWheelDiameter) / kGearRatio / 60;
private final double kPositionConversionRatio = (Math.PI * kWheelDiameter) / kGearRatio;
private final double kVelocityConversionRatio = kPositionConversionRatio / 60;

// setup feedforward
private final double ksShooterVolts = 0.17875;
Expand Down Expand Up @@ -63,6 +64,7 @@ public ShooterSubsystem() {

// allow us to read the encoder
m_ShooterMainEncoder = m_ShooterMotorMain.getEncoder();
m_ShooterMainEncoder.setPositionConversionFactor(kPositionConversionRatio);
m_ShooterMainEncoder.setVelocityConversionFactor(kVelocityConversionRatio);
// PID coefficients
kP = 0.00032423;
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/subsystems/UltrasonicSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

/** This Subsystem is what translates the output of the ultrasonic sensor to standard units. */
Expand Down Expand Up @@ -34,6 +35,7 @@ public void periodic() {
// SmartDashboard.putNumber("Ultrasonic Sensor Distance", getRangeInches(ultrasonic1));
// Calculate what percentage of 5 Volts we are actually at
voltageScaleFactor = 5 / RobotController.getVoltage5V();
SmartDashboard.putNumber("Ring Distance", DistanceIn());
}

@Override
Expand Down

0 comments on commit a74f32a

Please sign in to comment.