-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathCoreConstants.java
More file actions
117 lines (87 loc) · 4.41 KB
/
CoreConstants.java
File metadata and controls
117 lines (87 loc) · 4.41 KB
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
package frc.robot.core751;
import com.revrobotics.CANSparkMax.IdleMode;
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.interfaces.Gyro;
import edu.wpi.first.wpilibj2.command.button.Button;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc.robot.core751.commands.camera.LimeLight.SwitchCameraMode;
import frc.robot.core751.subsystems.camera.CamServer;
import frc.robot.core751.subsystems.camera.LimeLight;
import frc.robot.core751.subsystems.camera.PhotonVision;
import frc.robot.core751.subsystems.drivetrain.DifferentialDriveTrain;
import frc.robot.core751.subsystems.drivetrain.DifferentialDriveTrain.driveMotor;
import frc.robot.core751.wrappers.OverrideableJoystick;
import frc.robot.core751.wrappers.wCamera;
public final class CoreConstants{
public enum Controller { // Button mappings for the XBOX One controller
A(1), B(2), X(3), Y(4), LB(5), RB(6),
LT(2), // Must use .getRawAxis()
RT(3), // Must use .getRaxAxis()
BACK(7), START(8),
LEFT_AXIS_PRESS(9), // X-Axis: -1.000 to 1.000 (stick.GetX())
RIGHT_AXIS_PRESS(10); // Y-Axis: -1.000 to 1.000 (stick.GetY())
private int buttonNum;
private Controller(int value) {
this.buttonNum = value;
}
public int getButtonMapping() {
return this.buttonNum;
}
}
/*-------------/
/--DriveTrain--/
/-------------*/
public static int driveStickPort = 0;
public static OverrideableJoystick driverStick = new OverrideableJoystick(CoreConstants.driveStickPort);
public static int leftDrivetrainIDs[] = new int[] { 1, 2, 3 };
public static int rightDrivetrainIDs[] = new int[] { 4, 5, 6 };
public static DifferentialDriveTrain.SmartControllerProfile driveMotorProfile= new DifferentialDriveTrain.SmartControllerProfile(IdleMode.kCoast, 0.25, 35);
public static DifferentialDriveTrain.driveMotor driveTrainMotorType = driveMotor.kSparkMaxBrushless;
public static boolean driveInvertLeft = false;
public static boolean driveInvertRight = true;
public static double speedCap = 0.5; //Deprecating
public static double driveTrainMaxSpeedMetersPerSecond = 1; //3 maybe?
public static Boolean smoothing = true;
public static double maxSparkDeccelPeriod = 1;//0.5;
public static double sparkDeccelThreshold = 0.5;
public static int sparkDeccelSteps = 14;//7;
public static double minPauseDeaccelThreshold = 0.5;
public static Button driveSwitchDirectionButton = new JoystickButton(driverStick, Controller.START.buttonNum);
/*-------------/
/----Camera----/
/-------------*/
//public static wCamera frontCamera = new wCamera(0);
public static wCamera[] allCameras = {}; //Just for usb camera
//public static CamServer camServer = new CamServer(frontCamera);
public static int mainPipeline = 1;
public static PhotonVision photonVision = new PhotonVision();
/*--------------/
/-----Auton-----/
/--------------*/
public static Gyro gyro = new ADXRS450_Gyro();
static{
gyro.calibrate();
}
public static double trackwidthMeters = 0.66; //Find experminetally if needed
public static DifferentialDriveKinematics driveKinematics =
new DifferentialDriveKinematics(trackwidthMeters);
public static double gearRatio = 7.44; //Gear ratio of drivetrain
public static int encoderCPR = 1; // 1 for NEO
public static double wheelDiameterMeters = 0.203;
public static double encoderDistancePerPulse =
(wheelDiameterMeters * Math.PI) / (double) encoderCPR / gearRatio;
public static double planningVoltageContraint = 5;
//-----------Feed Forward------------ (Remember to make these match your drivetrain)
public static double ksVolts = 0.14529;
public static double kvVoltSecondsPerMeter = 1.4637;
public static double kaVoltSecondsSquaredPerMeter = 0.25498;
public static double kPDriveVel = 1.3387;
//-------------Ramsete---------------
public static final double maxSpeedMetersPerSecond = 1; //Essentially Speedcap
public static final double maxAccelerationMetersPerSecondSquared = 3; //Essentially rotatonial speed
public static final double ramseteB = 2; // Reasonable baseline value
public static final double ramseteZeta = 0.7; // Reasonable baseline value
}