Skip to content

Commit

Permalink
fixed null pointer exception
Browse files Browse the repository at this point in the history
  • Loading branch information
ProgrammingSR committed Feb 25, 2024
1 parent e6b8c51 commit 7ff9511
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -205,12 +205,16 @@ public void addVisionMeasurement(Measurement measurement) {
m_poseEstimator.addVisionMeasurement(measurement.pose.toPose2d(), measurement.timestamp);
}

public void autonDrive(ChassisSpeeds desiredChassisSpeeds) {
swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(desiredChassisSpeeds);
}

/**
* Sets the swerve ModuleStates. Overloaded for either auton builder or teleop.
*
* @param desiredStates The desired SwerveModule states.
*/
public void setModuleStates(SwerveModuleState[] desiredStates) {
private void setModuleStates(SwerveModuleState[] desiredStates) {
SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, DriveConstants.kMaxSpeedMetersPerSecond);

m_frontLeft.setDesiredState(desiredStates[0]);
Expand All @@ -233,8 +237,4 @@ public void setModuleStates(SwerveModuleState[] desiredStates) {
* Robot.kDefaultPeriod;
}

public void autonDrive(ChassisSpeeds desiredChassisSpeeds) {
swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(desiredChassisSpeeds);
}

}
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/VisionSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package frc.robot.subsystems;

import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import java.util.function.Consumer;
Expand Down Expand Up @@ -56,7 +57,7 @@ public class VisionSubsystem extends SubsystemBase {

private final IntegerSubscriber m_tv;

private List<Consumer<Measurement>> m_consumerList;
private List<Consumer<Measurement>> m_consumerList = new ArrayList<>(3);

/** Creates a new Limelight. */
public VisionSubsystem() {
Expand Down

0 comments on commit 7ff9511

Please sign in to comment.