package edu.wpi.first.wpilibj.examples.simpledifferentialdrivesimulation;
import edu.wpi.first.math.controller.PIDController;
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.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.AnalogGyroSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
public class Drivetrain {
public static final double kMaxSpeed = 3.0; // meters per second
public static final double kMaxAngularSpeed = Math.PI; // 1/2 rotation per second
private static final double kTrackWidth = 0.381 * 2;
private static final double kWheelRadius = 0.0508;
private final PWMSparkMax m_leftLeader = new PWMSparkMax(1);
private final PWMSparkMax m_rightLeader = new PWMSparkMax(3);
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final PIDController m_leftPIDController = new PIDController(8.5, 0, 0);
private final PIDController m_rightPIDController = new PIDController(8.5, 0, 0);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final DifferentialDriveKinematics m_kinematics =
new DifferentialDriveKinematics(kTrackWidth);
private final DifferentialDriveOdometry m_odometry =
new DifferentialDriveOdometry(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
// Simulation classes
private final AnalogGyroSim m_gyroSim = new AnalogGyroSim(m_gyro);
private final EncoderSim m_leftEncoderSim = new EncoderSim(m_leftEncoder);
private final EncoderSim m_rightEncoderSim = new EncoderSim(m_rightEncoder);
private final Field2d m_fieldSim = new Field2d();
private final DifferentialDrivetrainSim m_drivetrainSimulator =
new DifferentialDrivetrainSim(
LinearSystemId.identifyDrivetrainSystem(1.98, 0.2, 1.5, 0.3),
DCMotor.getCIM(2),
8,
kTrackWidth,
kWheelRadius,
null);
public Drivetrain() {
m_rightLeader.setInverted(true);
m_leftEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / 4096);
m_rightEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / 4096);
SmartDashboard.putData("Field", m_fieldSim);
}
/** Sets speeds to the drivetrain motors. */
public void setSpeeds(DifferentialDriveWheelSpeeds speeds) {
final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
double leftOutput =
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
double rightOutput =
m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
}
public void drive(double xSpeed, double rot) {
setSpeeds(m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0, rot)));
}
public void resetOdometry(Pose2d pose) {
m_drivetrainSimulator.setPose(pose);
m_odometry.resetPosition(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), pose);
}
public Pose2d getPose() {
return m_odometry.getPoseMeters();
}
/** Update our simulation. */
public void simulationPeriodic() {
m_drivetrainSimulator.setInputs(
m_leftLeader.get() * RobotController.getInputVoltage(),
m_rightLeader.get() * RobotController.getInputVoltage());
m_drivetrainSimulator.update(0.02);
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocityMetersPerSecond());
m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPositionMeters());
m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocityMetersPerSecond());
m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
}
/** Update odometry. */
public void periodic() {
m_odometry.update(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
m_fieldSim.setRobotPose(m_odometry.getPoseMeters());
}
}