summaryrefslogtreecommitdiff
path: root/src/main/java/frc/robot/subsystems/Drivetrain.java
blob: 80ed06e6ba494936ee931754318eda3c9d9fdf92 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
package frc.robot.subsystems;

import com.revrobotics.CANSparkMax;

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.wpilibj.Encoder;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
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 = 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 Encoder m_encoderL = Constants.encoderL;
    private Encoder m_encoderR = Constants.encoderR;

    private SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1.5, 2.82, 0.47);

    private final PIDController m_pidL = new PIDController(1, 0, 0);
    private final PIDController m_pidR = new PIDController(1, 0, 0);
    
    private DifferentialDriveKinematics m_kinematics = 
        new DifferentialDriveKinematics(Constants.TrackWidth);

    private DifferentialDriveOdometry m_odometry;

    public Drivetrain()
    {
        m_gyro.reset();
        m_gyro.calibrateGyro(10000);

        m_motorR_follower.follow(m_motorR_leader);
        m_motorL_follower.follow(m_motorL_leader);
        m_motorR_leader.setInverted(true);

        m_encoderL.setDistancePerPulse(-2 * Math.PI * Constants.WheelRadius / Constants.EncoderResolution);
        m_encoderR.setDistancePerPulse(2 * Math.PI * Constants.WheelRadius / Constants.EncoderResolution);
        
        m_encoderL.reset();
        m_encoderR.reset();

        m_odometry = new DifferentialDriveOdometry(
            m_gyro.toRotation2d(),
            Constants.encoderL.getDistance(),
            Constants.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) 
    {
        m_motorL_leader.setVoltage(
            m_pidL.calculate(m_encoderL.getRate(), speeds.leftMetersPerSecond)
            + m_feedforward.calculate(speeds.leftMetersPerSecond)
        );

        m_motorR_leader.setVoltage(
            m_pidR.calculate(m_encoderR.getRate(), speeds.rightMetersPerSecond)
            + m_feedforward.calculate(speeds.rightMetersPerSecond)
        );
    }

    public Pose2d pose2d() 
    {
        System.out.println("Distance: "+m_encoderL.getDistance());
        System.out.println("Distance: "+m_encoderR.getDistance());
        return m_odometry.getPoseMeters();
    }

    public void reset() 
    {
        m_gyro.reset();
        m_encoderL.reset();
        m_encoderR.reset();
        m_odometry = new DifferentialDriveOdometry(
            m_gyro.toRotation2d(),
            Constants.encoderL.getDistance(),
            Constants.encoderR.getDistance());
    }    

    @Override
    public void periodic() 
    {
        m_gyro.update();

        m_odometry.update(
            m_gyro.toRotation2d(),
            m_encoderL.getDistance(),
            m_encoderR.getDistance());
    }

    @Override
    public void simulationPeriodic() {
        // This method will be called once per scheduler run during simulation
    }
}