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; import edu.wpi.first.math.controller.RamseteController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.math.kinematics.DifferentialDriveKinematics; import edu.wpi.first.math.kinematics.DifferentialDriveOdometry; import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.math.trajectory.Trajectory; import edu.wpi.first.math.trajectory.TrajectoryConfig; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; import edu.wpi.first.units.Velocity; import edu.wpi.first.units.Voltage; import edu.wpi.first.units.MutableMeasure; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.RamseteCommand; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import static edu.wpi.first.units.MutableMeasure.mutable; import static edu.wpi.first.units.Units.Volts; import org.littletonrobotics.junction.Logger; import static edu.wpi.first.units.Units.Meters; import static edu.wpi.first.units.Units.MetersPerSecond; import frc.robot.Constants; import frc.robot.util.IMUGyro; public class Drivetrain extends SubsystemBase { private IMUGyro m_gyro = Constants.gyro; 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 = 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 = new SimpleMotorFeedforward(Constants.MotorkS, Constants.MotorkV); private final double kP = 0.363; private ProfiledPIDController m_pidL = new ProfiledPIDController(kP, 0, 0, Constants.motor_constraints); private ProfiledPIDController m_pidR = new ProfiledPIDController(kP, 0, 0, Constants.motor_constraints); private DifferentialDriveKinematics m_kinematics = new DifferentialDriveKinematics(Constants.TrackWidth); private DifferentialDriveOdometry m_odometry; // For system identification private final MutableMeasure m_voltage = mutable(Volts.of(0)); private final MutableMeasure m_distance = mutable(Meters.of(0)); private final MutableMeasure> m_velocity = mutable(MetersPerSecond.of(0)); private final SysIdRoutine m_sysIdRoutine = new SysIdRoutine( new SysIdRoutine.Config(), new SysIdRoutine.Mechanism( (Measure volts) -> { m_motorL_leader.setVoltage(volts.in(Volts)); m_motorR_leader.setVoltage(volts.in(Volts)); }, log -> { log.motor("drive-left") .voltage( m_voltage.mut_replace( m_motorL_leader.getAppliedOutput() * m_motorL_leader.getBusVoltage(), Volts) ) .linearPosition(m_distance.mut_replace(m_encoderL.getDistance(), Meters)) .linearVelocity(m_velocity.mut_replace(m_encoderL.getRate(), MetersPerSecond)); log.motor("driver-right") .voltage( m_voltage.mut_replace( m_motorR_leader.getAppliedOutput() * m_motorR_follower.getBusVoltage(), Volts) ) .linearPosition(m_distance.mut_replace(m_encoderR.getDistance(), Meters)) .linearVelocity(m_velocity.mut_replace(m_encoderR.getRate(), MetersPerSecond)); }, this)); public final TrajectoryConfig trajectoyConfig = new TrajectoryConfig( Constants.AutonomousMaxSpeed, Constants.AutonomousMaxAcceleration) .setKinematics(m_kinematics); public Drivetrain() { m_gyro.reset(); m_gyro.calibrateGyro(10000); m_motorR_follower.follow(m_motorR_leader); m_motorL_follower.follow(m_motorL_leader); m_motorL_leader.setInverted(true); m_encoderL.setReverseDirection(true); m_encoderL.setDistancePerPulse(Math.PI * Constants.WheelDiameter / 10.71 / Constants.EncoderResolution); m_encoderR.setDistancePerPulse(Math.PI * Constants.WheelDiameter / 10.71 / Constants.EncoderResolution); m_encoderL.reset(); m_encoderR.reset(); m_odometry = new DifferentialDriveOdometry( m_gyro.toRotation2d(), m_encoderL.getDistance(), m_encoderR.getDistance()); } // speed - linear velocity in m/s // rot - angular velocity in rad/s public void arcade(double speed, double rot) { speed(m_kinematics.toWheelSpeeds(new ChassisSpeeds(speed, 0.0, rot))); } // in m/s public void tank(double left, double right) { speed(new DifferentialDriveWheelSpeeds(left, right)); } public void speed(DifferentialDriveWheelSpeeds speeds) { Logger.recordOutput(getName() + "/leftSpeed", speeds.leftMetersPerSecond); Logger.recordOutput(getName() + "/rightSpeed", speeds.rightMetersPerSecond); voltage( m_pidL.calculate(m_encoderL.getRate(), speeds.leftMetersPerSecond) + m_feedforward.calculate(speeds.leftMetersPerSecond), m_pidR.calculate(m_encoderR.getRate(), speeds.rightMetersPerSecond) + m_feedforward.calculate(speeds.rightMetersPerSecond) ); } public void voltage(double leftVolts, double rightVolts) { Logger.recordOutput(getName() + "/leftVolts", leftVolts); Logger.recordOutput(getName() + "/rightVolts", rightVolts); m_motorL_leader.setVoltage(leftVolts); m_motorR_leader.setVoltage(rightVolts); } public Pose2d pose2d() { return m_odometry.getPoseMeters(); } public void reset() { m_gyro.reset(); m_encoderL.reset(); m_encoderR.reset(); m_odometry = new DifferentialDriveOdometry( m_gyro.toRotation2d(), m_encoderL.getDistance(), m_encoderR.getDistance()); } @Override public void periodic() { m_gyro.update(); m_odometry.update( m_gyro.toRotation2d(), m_encoderL.getDistance(), m_encoderR.getDistance()); Logger.recordOutput(getName() + "/gyro", m_gyro.toRotation2d().getDegrees()); Logger.recordOutput(getName() + "/pose", pose2d()); Logger.recordOutput(getName() + "/encoderRateL", m_encoderL.getRate()); Logger.recordOutput(getName() + "/encoderRateR", m_encoderR.getRate()); Logger.recordOutput(getName() + "/encoderDL", m_encoderL.getDistance()); Logger.recordOutput(getName() + "/encoderDR", m_encoderR.getDistance()); } public Command followTrajectory(Trajectory trajectory) { RamseteCommand ramsete = new RamseteCommand( trajectory, this::pose2d, new RamseteController(2.0, 0.7), m_feedforward, m_kinematics, () -> new DifferentialDriveWheelSpeeds(m_encoderL.getRate(), m_encoderR.getRate()), new PIDController(kP, 0, 0), new PIDController(kP, 0, 0), this::voltage, this); return Commands.runOnce(() -> this.reset()) .andThen(ramsete) .andThen(Commands.runOnce(() -> voltage(0, 0))); } public Command sysIdQausistatic(SysIdRoutine.Direction direction) { return m_sysIdRoutine.quasistatic(direction); } public Command sysIdDynamic(SysIdRoutine.Direction direction) { return m_sysIdRoutine.dynamic(direction); } }