summaryrefslogtreecommitdiff
path: root/src/main/java/frc/robot/Constants.java
blob: efff2b8a6961bee0bea886a915067d9903661fc8 (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
package frc.robot;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.I2C;
import edu.wpi.first.wpilibj.I2C.Port;
import frc.robot.util.IMUGyro;

public class Constants
{
    public static final GenericHID controller = new GenericHID(0);
    public static final GenericHID controller2 = new GenericHID(1);

    public static final double InputSmoothing = 0.1;

    public static final double DriveMaxSpeed = 5; // m/s
    public static final double DriveMaxAcceleration = 5; // m/s^2
    public static final double DriveMaxAngular = Math.PI; // rad/s?

    public static final double AutonomousMaxSpeed = 0.5; // m/s
    public static final double AutonomousMaxAcceleration = 0.25; // m/s^2

    // for Drivetrain
    public static final double WheelDiameter = Units.inchesToMeters(6); // in meters
    public static final double TrackWidth = 0.58;  // in meters
    public static final double EncoderResolution = 16;

    public static final IMUGyro gyro = new IMUGyro(new I2C(Port.kOnboard, 0x68));

    public static final TrapezoidProfile.Constraints motor_constraints = 
        new TrapezoidProfile.Constraints(DriveMaxSpeed, DriveMaxAcceleration);
    public static final SimpleMotorFeedforward motor_feedforward = new SimpleMotorFeedforward(0.54082, 2.4705);

    public static final CANSparkMax motorL_leader = new CANSparkMax(11, MotorType.kBrushed);
    public static final CANSparkMax motorL_follower = new CANSparkMax(12, MotorType.kBrushed);
    public static final CANSparkMax motorR_leader = new CANSparkMax(13, MotorType.kBrushed);
    public static final CANSparkMax motorR_follower = new CANSparkMax(14, MotorType.kBrushed);

    public static final Encoder encoderL = new Encoder(6, 7); 
    public static final Encoder encoderR = new Encoder(4, 5);

    // for Intake
    public static final int intakeT_ID = 32;
    public static final int intakeD_ID = 31;

    // for Shooter    CommandScheduler.getInstance().run();

    public static final int shooterT_ID = 21;
    public static final int shooterD_ID = 22;

    // for Arm
    public static final double ArmGearReduction = 60;

    public static final double ArmEpsilon = 3 * Math.PI/180;

    public static final double ArmkS = 0.4;
    public static final double ArmkG = 0.495;
    public static final double ArmkV = 0;

    public static final double arm_initial_position = -43.0 * Math.PI / 180.0;
    public static final TrapezoidProfile.Constraints arm_constraints = 
        new TrapezoidProfile.Constraints(7, 5);

    public static final double ArmkP = 11.5;
    public static final double ArmkI = 0.0;
    public static final double ArmkD = 0.4;

    public static final int armL_ID = 41;
    public static final int armR_ID = 42;

    // for Chain 
    public static final double ChainEncoderScale = 3000;

    public static final double ChainEpsilon = 0.05;

    public static final TrapezoidProfile.Constraints chain_constraints = 
        new TrapezoidProfile.Constraints(5, 5);

    public static final double ChainkP = 45.0;
    public static final double ChainkI = 0.0;
    public static final double ChainkD = 0.0;

    public static final int chain_ID = 50;
    public static final int[] chain_encoder_PINS = {8, 9};

    // Hooks
    public static final int hookL_ID = 62;
    public static final int hookR_ID = 61;
}