mirror of
https://github.com/Team4388/2026KPopRobotHunters.git
synced 2026-06-09 08:48:05 -06:00
Remove angle and pitch motors. Clean some stuff up.
This commit is contained in:
@@ -1,58 +0,0 @@
|
||||
package frc4388.robot.subsystems.lidar;
|
||||
|
||||
import org.littletonrobotics.junction.Logger;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc4388.robot.constants.Constants.LiDARConstants;
|
||||
import frc4388.utility.status.Status;
|
||||
import frc4388.utility.status.FaultReporter;
|
||||
import frc4388.utility.status.Queryable;
|
||||
import frc4388.utility.status.Status.ReportLevel;
|
||||
|
||||
public class LiDAR extends SubsystemBase implements Queryable {
|
||||
LidarIO io;
|
||||
LidarStateAutoLogged state = new LidarStateAutoLogged();
|
||||
|
||||
private String name = "Lidar";
|
||||
|
||||
public LiDAR(LidarIO device, String name) {
|
||||
FaultReporter.register(this);
|
||||
|
||||
this.io = device;
|
||||
this.name = name;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
io.updateInputs(state);
|
||||
Logger.processInputs("LiDAR/"+name, state);
|
||||
}
|
||||
|
||||
// @AutoLogOutput(key = "Lidar/{name}")
|
||||
public double getDistance(){
|
||||
return state.distance;
|
||||
}
|
||||
|
||||
public boolean withinDistance(){
|
||||
if(state.distance == -1) return false;
|
||||
return state.distance < LiDARConstants.LIDAR_DETECT_DISTANCE;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getName() {
|
||||
return "Lidar " + name;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Status diagnosticStatus() {
|
||||
Status s = new Status();
|
||||
|
||||
if(state.distance == -1)
|
||||
s.addReport(ReportLevel.ERROR, "LiDAR DISCONNECTED");
|
||||
|
||||
s.addReport(ReportLevel.INFO, "LiDAR Distance: " + state.distance);
|
||||
|
||||
return s;
|
||||
}
|
||||
|
||||
}
|
||||
@@ -1,13 +0,0 @@
|
||||
package frc4388.robot.subsystems.lidar;
|
||||
|
||||
import org.littletonrobotics.junction.AutoLog;
|
||||
|
||||
public interface LidarIO {
|
||||
@AutoLog
|
||||
public class LidarState {
|
||||
public boolean connected;
|
||||
public double distance;
|
||||
}
|
||||
|
||||
public default void updateInputs(LidarState state) {}
|
||||
}
|
||||
@@ -1,27 +0,0 @@
|
||||
package frc4388.robot.subsystems.lidar;
|
||||
|
||||
import edu.wpi.first.wpilibj.Counter;
|
||||
import frc4388.robot.constants.Constants.LiDARConstants;
|
||||
|
||||
// https://girlsofsteeldocs.readthedocs.io/en/latest/technical-resources/sensors/LIDAR-Lite-Distance-Sensor.html#minimal-roborio-interface
|
||||
public class LidarReal implements LidarIO {
|
||||
|
||||
|
||||
private Counter LidarPWM;
|
||||
|
||||
public LidarReal(int port) {
|
||||
LidarPWM = new Counter(port);
|
||||
LidarPWM.setMaxPeriod(1.00); //set the max period that can be measured
|
||||
LidarPWM.setSemiPeriodMode(true); //Set the counter to period measurement
|
||||
LidarPWM.reset();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateInputs(LidarState state) {
|
||||
|
||||
if(LidarPWM.get() < 1)
|
||||
state.distance = -1;
|
||||
else
|
||||
state.distance = (LidarPWM.getPeriod() * LiDARConstants.SECONDS_TO_MICROS) / LiDARConstants.LIDAR_MICROS_TO_CM;
|
||||
}
|
||||
}
|
||||
@@ -8,10 +8,11 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration;
|
||||
import com.ctre.phoenix6.signals.NeutralModeValue;
|
||||
|
||||
import edu.wpi.first.units.measure.Angle;
|
||||
import frc4388.utility.status.CanDevice;
|
||||
|
||||
public class ShooterConstants {
|
||||
// Motor conversions
|
||||
public static final double ANGLE_MOTOR_GEAR_RATIO = 1.;
|
||||
// public static final double ANGLE_MOTOR_GEAR_RATIO = 1.;
|
||||
public static final double PITCH_MOTOR_GEAR_RATIO = 1.;
|
||||
public static final double FLYWHEEL_GEAR_RATIO = 1.;
|
||||
public static final double FEEDER_INCHES_PER_ROT = 1.;
|
||||
@@ -20,24 +21,29 @@ public class ShooterConstants {
|
||||
|
||||
// 0 is the forward angle on the robot.
|
||||
// negative is left, positive is right
|
||||
public static final Angle ANGLE_LIMIT_LEFT = Degrees.of(-180);
|
||||
public static final Angle ANGLE_LIMIT_RIGHT = Degrees.of(180);
|
||||
// public static final Angle ANGLE_LIMIT_LEFT = Degrees.of(-180);
|
||||
// public static final Angle ANGLE_LIMIT_RIGHT = Degrees.of(180);
|
||||
|
||||
// 0 is paralell to the ground, 90 is directly up
|
||||
public static final Angle PITCH_LIMIT_UPPER = Degrees.of(90);
|
||||
public static final Angle PITCH_LIMIT_LOWER = Degrees.of(0);
|
||||
|
||||
// Motor configs
|
||||
public static final TalonFXConfiguration ANGLE_MOTOR_CONFIG = new TalonFXConfiguration()
|
||||
.withCurrentLimits(
|
||||
new CurrentLimitsConfigs()
|
||||
.withStatorCurrentLimit(40) // TODO: tune???
|
||||
.withStatorCurrentLimitEnable(true)
|
||||
).withMotorOutput(
|
||||
new MotorOutputConfigs()
|
||||
.withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
|
||||
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
||||
);
|
||||
// public static final TalonFXConfiguration ANGLE_MOTOR_CONFIG = new TalonFXConfiguration()
|
||||
// .withCurrentLimits(
|
||||
// new CurrentLimitsConfigs()
|
||||
// .withStatorCurrentLimit(40) // TODO: tune???
|
||||
// .withStatorCurrentLimitEnable(true)
|
||||
// ).withMotorOutput(
|
||||
// new MotorOutputConfigs()
|
||||
// .withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
|
||||
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
||||
// );
|
||||
|
||||
public static final class IDs {
|
||||
public static final CanDevice FLYWHEEK_CAN_DEVICE = new CanDevice("Flywheel", 22);
|
||||
}
|
||||
|
||||
public static final TalonFXConfiguration PITCH_MOTOR_CONFIG = new TalonFXConfiguration()
|
||||
.withCurrentLimits(
|
||||
new CurrentLimitsConfigs()
|
||||
|
||||
@@ -16,13 +16,13 @@ import edu.wpi.first.units.measure.LinearVelocity;
|
||||
public interface ShooterIO {
|
||||
@AutoLog
|
||||
public class ShooterState {
|
||||
Angle shooterAngle = Rotations.of(0);
|
||||
Angle shooterTargetAngle = Rotations.of(0);
|
||||
Current angleMotorCurrent = Amps.of(0);
|
||||
// Angle shooterAngle = Rotations.of(0);
|
||||
// Angle shooterTargetAngle = Rotations.of(0);
|
||||
// Current angleMotorCurrent = Amps.of(0);
|
||||
|
||||
Angle shooterPitch = Rotations.of(0);
|
||||
Angle shooterTargetPitch = Rotations.of(0);
|
||||
Current pitchMotorCurrent = Amps.of(0);
|
||||
// Angle shooterPitch = Rotations.of(0);
|
||||
// Angle shooterTargetPitch = Rotations.of(0);
|
||||
// Current pitchMotorCurrent = Amps.of(0);
|
||||
|
||||
AngularVelocity flywheelVelocity = RotationsPerSecond.of(0);
|
||||
AngularVelocity flywheelTargetVelocity = RotationsPerSecond.of(0);
|
||||
@@ -33,8 +33,8 @@ public interface ShooterIO {
|
||||
Current feederMotorCurrent = Amps.of(0);
|
||||
}
|
||||
|
||||
public default void setShooterAngle(ShooterState state, Angle angle) {}
|
||||
public default void setShooterPitch(ShooterState state, Angle angle) {}
|
||||
// public default void setShooterAngle(ShooterState state, Angle angle) {}
|
||||
// public default void setShooterPitch(ShooterState state, Angle angle) {}
|
||||
public default void setFlywheelVelocity(ShooterState state, AngularVelocity angularVelocity) {}
|
||||
public default void setFeederVelocity(ShooterState state, LinearVelocity linearVelocity) {}
|
||||
|
||||
|
||||
@@ -12,25 +12,25 @@ import edu.wpi.first.units.measure.*;
|
||||
|
||||
public class ShooterReal implements ShooterIO {
|
||||
|
||||
TalonFX m_angleMotor;
|
||||
TalonFX m_pitchMotor;
|
||||
// TalonFX m_angleMotor;
|
||||
// TalonFX m_pitchMotor;
|
||||
TalonFX m_flywheelMotor;
|
||||
TalonFX m_feederMotor;
|
||||
|
||||
public ShooterReal(
|
||||
TalonFX angleMotor,
|
||||
TalonFX pitchMotor,
|
||||
// TalonFX angleMotor,
|
||||
// TalonFX pitchMotor,
|
||||
TalonFX flywheelMotor,
|
||||
TalonFX feederMotor
|
||||
) {
|
||||
m_angleMotor = angleMotor;
|
||||
m_pitchMotor = pitchMotor;
|
||||
// m_angleMotor = angleMotor;
|
||||
// m_pitchMotor = pitchMotor;
|
||||
m_flywheelMotor = flywheelMotor;
|
||||
m_feederMotor = feederMotor;
|
||||
|
||||
// Apply the configs
|
||||
m_angleMotor.getConfigurator().apply(ShooterConstants.ANGLE_MOTOR_CONFIG);
|
||||
m_pitchMotor.getConfigurator().apply(ShooterConstants.PITCH_MOTOR_CONFIG);
|
||||
// m_angleMotor.getConfigurator().apply(ShooterConstants.ANGLE_MOTOR_CONFIG);
|
||||
// m_pitchMotor.getConfigurator().apply(ShooterConstants.PITCH_MOTOR_CONFIG);
|
||||
m_flywheelMotor.getConfigurator().apply(ShooterConstants.FLYWHEEL_MOTOR_CONFIG);
|
||||
m_feederMotor.getConfigurator().apply(ShooterConstants.FEEDER_MOTOR_CONFIG);
|
||||
}
|
||||
@@ -45,35 +45,35 @@ public class ShooterReal implements ShooterIO {
|
||||
}
|
||||
}
|
||||
|
||||
// TODO: Test
|
||||
@Override
|
||||
public void setShooterAngle(ShooterState state, Angle angle) {
|
||||
state.shooterTargetAngle = angle;
|
||||
// Assume that the angle is always accurate, because I think we will use a shaft encoder
|
||||
// Assume that 0 degrees = forwards. Might need an offset here
|
||||
// // TODO: Test
|
||||
// @Override
|
||||
// public void setShooterAngle(ShooterState state, Angle angle) {
|
||||
// state.shooterTargetAngle = angle;
|
||||
// // Assume that the angle is always accurate, because I think we will use a shaft encoder
|
||||
// // Assume that 0 degrees = forwards. Might need an offset here
|
||||
|
||||
Angle boundedAngle = clampAng(angle, ShooterConstants.ANGLE_LIMIT_LEFT, ShooterConstants.ANGLE_LIMIT_RIGHT);
|
||||
// (REAL_ROT) * (MOTOR_ROT / REAL_ROT) = MOTOR_ROT
|
||||
double motorTargetAngle = boundedAngle.in(Rotations) / ShooterConstants.ANGLE_MOTOR_GEAR_RATIO;
|
||||
PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
|
||||
m_angleMotor.setControl(posRequest);
|
||||
}
|
||||
// Angle boundedAngle = clampAng(angle, ShooterConstants.ANGLE_LIMIT_LEFT, ShooterConstants.ANGLE_LIMIT_RIGHT);
|
||||
// // (REAL_ROT) * (MOTOR_ROT / REAL_ROT) = MOTOR_ROT
|
||||
// double motorTargetAngle = boundedAngle.in(Rotations) / ShooterConstants.ANGLE_MOTOR_GEAR_RATIO;
|
||||
// PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
|
||||
// m_angleMotor.setControl(posRequest);
|
||||
// }
|
||||
|
||||
|
||||
// TODO: Test
|
||||
@Override
|
||||
public void setShooterPitch(ShooterState state, Angle angle) {
|
||||
state.shooterTargetPitch = angle;
|
||||
// TODO: Test
|
||||
// This assumes that the 0 is paralell to the ground. Might need an offset here
|
||||
// @Override
|
||||
// public void setShooterPitch(ShooterState state, Angle angle) {
|
||||
// state.shooterTargetPitch = angle;
|
||||
// // TODO: Test
|
||||
// // This assumes that the 0 is paralell to the ground. Might need an offset here
|
||||
|
||||
|
||||
Angle boundedAngle = clampAng(angle, ShooterConstants.PITCH_LIMIT_UPPER, ShooterConstants.PITCH_LIMIT_LOWER);
|
||||
// (REAL_ROT) * (MOTOR_ROT / REAL_ROT) = MOTOR_ROT
|
||||
double motorTargetAngle = boundedAngle.in(Rotations) / ShooterConstants.PITCH_MOTOR_GEAR_RATIO;
|
||||
PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
|
||||
m_angleMotor.setControl(posRequest);
|
||||
}
|
||||
// Angle boundedAngle = clampAng(angle, ShooterConstants.PITCH_LIMIT_UPPER, ShooterConstants.PITCH_LIMIT_LOWER);
|
||||
// // (REAL_ROT) * (MOTOR_ROT / REAL_ROT) = MOTOR_ROT
|
||||
// double motorTargetAngle = boundedAngle.in(Rotations) / ShooterConstants.PITCH_MOTOR_GEAR_RATIO;
|
||||
// PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
|
||||
// m_pitchMotor.setControl(posRequest);
|
||||
// }
|
||||
|
||||
@Override
|
||||
public void setFlywheelVelocity(ShooterState state, AngularVelocity angularVelocity) {
|
||||
@@ -95,11 +95,11 @@ public class ShooterReal implements ShooterIO {
|
||||
|
||||
@Override
|
||||
public void updateInputs(ShooterState state) {
|
||||
state.shooterAngle = m_angleMotor.getPosition().getValue().times(ShooterConstants.ANGLE_MOTOR_GEAR_RATIO);
|
||||
state.angleMotorCurrent = m_angleMotor.getStatorCurrent(false).getValue();
|
||||
// state.shooterAngle = m_angleMotor.getPosition().getValue().times(ShooterConstants.ANGLE_MOTOR_GEAR_RATIO);
|
||||
// state.angleMotorCurrent = m_angleMotor.getStatorCurrent(false).getValue();
|
||||
|
||||
state.shooterPitch = m_pitchMotor.getPosition().getValue().times(ShooterConstants.PITCH_MOTOR_GEAR_RATIO);
|
||||
state.pitchMotorCurrent = m_pitchMotor.getStatorCurrent().getValue();
|
||||
// state.shooterPitch = m_pitchMotor.getPosition().getValue().times(ShooterConstants.PITCH_MOTOR_GEAR_RATIO);
|
||||
// state.pitchMotorCurrent = m_pitchMotor.getStatorCurrent().getValue();
|
||||
|
||||
state.flywheelVelocity = m_flywheelMotor.getVelocity().getValue();
|
||||
state.flywheelMotorCurrent = m_flywheelMotor.getStatorCurrent().getValue();
|
||||
|
||||
Reference in New Issue
Block a user