Skip to content

Commit

Permalink
applied NeoConfig to all neos
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Jan 21, 2024
1 parent 54ab9f1 commit 51eb3c9
Show file tree
Hide file tree
Showing 8 changed files with 49 additions and 27 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public Shooter(ShooterSubsystem shooter) {
// Called when the command is initially scheduled.
@Override
public void initialize() {
_shooter.spinMotor();
_shooter.spinMotors();
}

// Called every time the scheduler runs while the command is scheduled.
Expand Down
12 changes: 7 additions & 5 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.utils.NeoConfig;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
Expand All @@ -27,17 +28,17 @@ public class ShooterSubsystem extends SubsystemBase {

/** Creates a new ShooterSubsystem. */
public ShooterSubsystem() {
_rightMotor.follow(_leftMotor,true);
NeoConfig.configureNeo(_leftMotor, true);
NeoConfig.configureFollowerNeo(_rightMotor, _leftMotor, true);
}


@Override
public void periodic() {
// This method will be called once per scheduler run
}

public void spinMotor() {
_leftMotor.set(-1.0);
public void spinMotors() {
_leftMotor.set(1.0);
}

public void stopMotors() {
Expand All @@ -48,14 +49,15 @@ public void stopMotors() {
public double getShooterVelocity(){
double neo_rps = _leftEncoder.getVelocity() / 60;

return(neo_rps / Constants.Physical.SHOOTER_GEAR_RATIO ) * Constants.Physical.SHOOTER_FLYWHEEL_CIRCUMFERENCE;
return (neo_rps / Constants.Physical.SHOOTER_GEAR_RATIO) * Constants.Physical.SHOOTER_FLYWHEEL_CIRCUMFERENCE;
}

/** Set the velocity of the back wheels in m/s. */
public void setVelocity(double velocity){
double flywheel_output = (velocity / Constants.Speeds.SHOOTER_MAX_SPEED); // FEEDFORWARD (main output)
double flywheel_pid = _shooterController.calculate(getShooterVelocity(), velocity); // PID for distrubances

// a similar controller setup can be found in SwerveModule
_leftMotor.set(flywheel_output + flywheel_pid);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ public void periodic() {
});

if (_visionSubsystem.isApriltagVisible()) {
_estimator.addVisionMeasurement(_visionSubsystem.getBotpose(), Timer.getFPGATimestamp());
_estimator.addVisionMeasurement(_visionSubsystem.get_botpose(), Timer.getFPGATimestamp());
}

_field.setRobotPose(_pose);
Expand Down
18 changes: 9 additions & 9 deletions src/main/java/frc/robot/subsystems/VisionSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@
* @author Alex Reyes
*/
public class VisionSubsystem extends SubsystemBase {
NetworkTableInstance inst = NetworkTableInstance.getDefault();
NetworkTable limelight = inst.getTable("limelight");
private final NetworkTableInstance _inst = NetworkTableInstance.getDefault();
private final NetworkTable _limelight = _inst.getTable("limelight");

private double[] botpose = new double[6];
private double[] _botpose = new double[6];

/** Creates a new VisionSubsystem. */
public VisionSubsystem() {}
Expand All @@ -33,12 +33,12 @@ public void periodic() {
// SmartDashboard.putData("Limelight Field", _field);
}

public Pose2d getBotpose() {
botpose = limelight.getEntry("botpose_wpiblue").getDoubleArray(botpose);
public Pose2d get_botpose() {
_botpose = _limelight.getEntry("botpose_wpiblue").getDoubleArray(_botpose);

double botposeX = botpose[0];
double botposeY = botpose[1];
double botposeYaw = Math.toRadians(botpose[5]);
double botposeX = _botpose[0];
double botposeY = _botpose[1];
double botposeYaw = Math.toRadians(_botpose[5]);

Rotation2d botposeRotation = new Rotation2d(botposeYaw);
Pose2d botPose2D = new Pose2d(botposeX, botposeY, botposeRotation);
Expand All @@ -48,7 +48,7 @@ public Pose2d getBotpose() {
}

public boolean isApriltagVisible() {
double tv = limelight.getEntry("tv").getDouble(0);
double tv = _limelight.getEntry("tv").getDouble(0);
if (tv == 0) {
return false;
}
Expand Down
17 changes: 17 additions & 0 deletions src/main/java/frc/robot/utils/NeoConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,30 @@
* @author Ze Rui Zheng
* @author Elvis Osmanov
*/

/** For configuring Neos (with CANSparkMax). */
public class NeoConfig {
/**
* Basic Neo (with CANSparkMax) config, sets Falcon to factory defaults, sets encoder to 0,
* and sets Neo to Brake neutral mode.
*
* @param neo - The CANSparkMax (with Neo) to configure.
* @param invert - Whether to invert the motor or not.
*/
public static void configureNeo(CANSparkMax neo, boolean invert) {
neo.setIdleMode(IdleMode.kCoast);
neo.enableSoftLimit(SoftLimitDirection.kForward, false);
neo.enableSoftLimit(SoftLimitDirection.kReverse, false);
neo.setInverted(invert);
}

/**
* Configure a follower of a master Neo motor.
*
* @param neo - The Neo (with CANSparkMax) to config.
* @param master - The master motor.
* @param opposeMaster - Whether to oppose the master or not.
*/
public static void configureFollowerNeo(CANSparkMax neo, CANSparkMax master, boolean opposeMaster) {
configureNeo(neo, false);
neo.follow(master);
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/utils/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ public class SwerveModule {
* Represents a single swerve module built with talons for rotation and drive control, and a
* cancoder for angle.
*
* @param driveMotorId CAN ID of drive motor.
* @param rotationMotorId CAN ID of rotation motor.
* @param encoderId CAN ID of cancoder.
* @param angleOffset Angle offset to add to the absolute cancoder.
* @param driveP kP for the drive controller.
* @param rotationP kP for the rotation controller.
* @param driveMotorId - CAN ID of drive motor.
* @param rotationMotorId - CAN ID of rotation motor.
* @param encoderId - CAN ID of cancoder.
* @param angleOffset - Angle offset to add to the absolute cancoder.
* @param driveP - kP for the drive controller.
* @param rotationP - kP for the rotation controller.
*/
public SwerveModule(
int driveMotorId,
Expand Down
9 changes: 6 additions & 3 deletions src/main/java/frc/robot/utils/TalonFXConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,18 +19,21 @@
public class TalonFXConfig {
/**
* Basic Falcon config, sets Falcon to factory defaults, sets encoder to 0, and sets Falcon
* deadband and sets Falcon to Brake neutral mode.
* deadband and sets Falcon to Coast neutral mode.
*
* @param falcon - The Falcon to config.
*
* @return The configuration object applied to the Falcon.
*/
public static TalonFXConfiguration configureFalcon(TalonFX falcon, boolean invert) {
// TODO: will prob need to add the code to zero encoder
TalonFXConfiguration config = new TalonFXConfiguration();

falcon.getConfigurator().DefaultTimeoutSeconds = Constants.CAN.CAN_TIMEOUT;
falcon.getConfigurator().refresh(config);

config.MotorOutput.DutyCycleNeutralDeadband = 0.01;
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
config.MotorOutput.DutyCycleNeutralDeadband = 0.01;
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;

config.MotorOutput.Inverted =
invert ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive;
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/utils/UtilFuncs.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@ public final class UtilFuncs {
/**
* Applies deadband to a certain value.
*
* @param val The value to deadband.
* @param deadband The deadband to apply.
* @param val - The value to deadband.
* @param deadband - The deadband to apply.
* @return The new value with deadband applied.
*/
public static double ApplyDeadband(double val, double deadband) {
Expand Down

0 comments on commit 51eb3c9

Please sign in to comment.