diff options
Diffstat (limited to 'src/main/java/frc/robot/subsystems/Drivetrain.java')
-rw-r--r-- | src/main/java/frc/robot/subsystems/Drivetrain.java | 23 |
1 files changed, 12 insertions, 11 deletions
diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java index aee9597..66d1ba6 100644 --- a/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -1,6 +1,7 @@ package frc.robot.subsystems; import com.revrobotics.CANSparkMax; +import com.revrobotics.CANSparkLowLevel.MotorType; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.ProfiledPIDController; @@ -40,15 +41,15 @@ public class Drivetrain extends SubsystemBase { private IMUGyro m_gyro = Constants.gyro; - private CANSparkMax m_motorL_leader = Constants.motorL_leader; - private CANSparkMax m_motorL_follower = Constants.motorL_follower; - private CANSparkMax m_motorR_leader = Constants.motorR_leader; - private CANSparkMax m_motorR_follower = Constants.motorR_follower; + private CANSparkMax m_motorL_leader = new CANSparkMax(Constants.motorL_leader_ID, MotorType.kBrushed); + private CANSparkMax m_motorL_follower = new CANSparkMax(Constants.motorL_follower_ID, MotorType.kBrushed); + private CANSparkMax m_motorR_leader = new CANSparkMax(Constants.motorR_leader_ID, MotorType.kBrushed); + private CANSparkMax m_motorR_follower = new CANSparkMax(Constants.motorR_follower_ID, MotorType.kBrushed); - private Encoder m_encoderL = Constants.encoderL; - private Encoder m_encoderR = Constants.encoderR; + private Encoder m_encoderL = new Encoder(Constants.encoderL_PINS[0], Constants.encoderL_PINS[1]); + private Encoder m_encoderR = new Encoder(Constants.encoderR_PINS[0], Constants.encoderR_PINS[1]); - private SimpleMotorFeedforward m_feedforward = Constants.motor_feedforward; + private SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(Constants.MotorkS, Constants.MotorkV); private final double kP = 0.363; @@ -116,8 +117,8 @@ public class Drivetrain extends SubsystemBase m_odometry = new DifferentialDriveOdometry( m_gyro.toRotation2d(), - Constants.encoderL.getDistance(), - Constants.encoderR.getDistance()); + m_encoderL.getDistance(), + m_encoderR.getDistance()); } // speed - linear velocity in m/s @@ -168,8 +169,8 @@ public class Drivetrain extends SubsystemBase m_odometry = new DifferentialDriveOdometry( m_gyro.toRotation2d(), - Constants.encoderL.getDistance(), - Constants.encoderR.getDistance()); + m_encoderL.getDistance(), + m_encoderR.getDistance()); } @Override |