From 7ff951112cd6bcbe52ee009dd12b034fd117eeee Mon Sep 17 00:00:00 2001 From: ProgrammingSR Date: Sat, 24 Feb 2024 16:38:32 -0800 Subject: [PATCH] fixed null pointer exception --- src/main/java/frc/robot/subsystems/DriveSubsystem.java | 10 +++++----- .../java/frc/robot/subsystems/VisionSubsystem.java | 3 ++- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/DriveSubsystem.java index b1e034b..dc822ef 100644 --- a/src/main/java/frc/robot/subsystems/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -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]); @@ -233,8 +237,4 @@ public void setModuleStates(SwerveModuleState[] desiredStates) { * Robot.kDefaultPeriod; } - public void autonDrive(ChassisSpeeds desiredChassisSpeeds) { - swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(desiredChassisSpeeds); - } - } diff --git a/src/main/java/frc/robot/subsystems/VisionSubsystem.java b/src/main/java/frc/robot/subsystems/VisionSubsystem.java index ebf72ce..33fa918 100644 --- a/src/main/java/frc/robot/subsystems/VisionSubsystem.java +++ b/src/main/java/frc/robot/subsystems/VisionSubsystem.java @@ -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; @@ -56,7 +57,7 @@ public class VisionSubsystem extends SubsystemBase { private final IntegerSubscriber m_tv; - private List> m_consumerList; + private List> m_consumerList = new ArrayList<>(3); /** Creates a new Limelight. */ public VisionSubsystem() {