mirror of
https://github.com/Team4388/Robot-Essentials.git
synced 2026-06-09 00:38:01 -06:00
Convert RobotTime into a singleton
This commit is contained in:
@@ -22,6 +22,7 @@ import frc4388.utility.RobotTime;
|
|||||||
public class Robot extends TimedRobot {
|
public class Robot extends TimedRobot {
|
||||||
Command m_autonomousCommand;
|
Command m_autonomousCommand;
|
||||||
|
|
||||||
|
private RobotTime m_robotTime = RobotTime.getInstance();
|
||||||
private RobotContainer m_robotContainer;
|
private RobotContainer m_robotContainer;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -45,7 +46,7 @@ public class Robot extends TimedRobot {
|
|||||||
*/
|
*/
|
||||||
@Override
|
@Override
|
||||||
public void robotPeriodic() {
|
public void robotPeriodic() {
|
||||||
RobotTime.updateTimes();
|
m_robotTime.updateTimes();
|
||||||
// Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
|
// Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
|
||||||
// commands, running already-scheduled commands, removing finished or interrupted commands,
|
// commands, running already-scheduled commands, removing finished or interrupted commands,
|
||||||
// and running subsystem periodic() methods. This must be called from the robot's periodic
|
// and running subsystem periodic() methods. This must be called from the robot's periodic
|
||||||
@@ -60,7 +61,7 @@ public class Robot extends TimedRobot {
|
|||||||
*/
|
*/
|
||||||
@Override
|
@Override
|
||||||
public void disabledInit() {
|
public void disabledInit() {
|
||||||
RobotTime.endMatchTime();
|
m_robotTime.endMatchTime();
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
@@ -85,7 +86,7 @@ public class Robot extends TimedRobot {
|
|||||||
if (m_autonomousCommand != null) {
|
if (m_autonomousCommand != null) {
|
||||||
m_autonomousCommand.schedule();
|
m_autonomousCommand.schedule();
|
||||||
}
|
}
|
||||||
RobotTime.startMatchTime();
|
m_robotTime.startMatchTime();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -104,7 +105,7 @@ public class Robot extends TimedRobot {
|
|||||||
if (m_autonomousCommand != null) {
|
if (m_autonomousCommand != null) {
|
||||||
m_autonomousCommand.cancel();
|
m_autonomousCommand.cancel();
|
||||||
}
|
}
|
||||||
RobotTime.startMatchTime();
|
m_robotTime.startMatchTime();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|||||||
@@ -25,15 +25,14 @@ import frc4388.utility.RobotGyro;
|
|||||||
public class RobotMap {
|
public class RobotMap {
|
||||||
|
|
||||||
public RobotMap() {
|
public RobotMap() {
|
||||||
configureLEDSubsystem();
|
configureLEDMotorControllers();
|
||||||
configureDriveSubsystem();
|
configureDriveMotorControllers();
|
||||||
}
|
}
|
||||||
|
|
||||||
/* LED Subsystem */
|
/* LED Subsystem */
|
||||||
public final Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
public final Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
||||||
|
|
||||||
void configureLEDSubsystem() {
|
void configureLEDMotorControllers() {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Drive Subsystem */
|
/* Drive Subsystem */
|
||||||
@@ -44,7 +43,7 @@ public class RobotMap {
|
|||||||
public final DifferentialDrive driveTrain = new DifferentialDrive(leftFrontMotor, rightFrontMotor);
|
public final DifferentialDrive driveTrain = new DifferentialDrive(leftFrontMotor, rightFrontMotor);
|
||||||
public final RobotGyro gyroDrive = new RobotGyro(new PigeonIMU(DriveConstants.DRIVE_PIGEON_ID));
|
public final RobotGyro gyroDrive = new RobotGyro(new PigeonIMU(DriveConstants.DRIVE_PIGEON_ID));
|
||||||
|
|
||||||
void configureDriveSubsystem() {
|
void configureDriveMotorControllers() {
|
||||||
|
|
||||||
/* factory default values */
|
/* factory default values */
|
||||||
leftFrontMotor.configFactoryDefault();
|
leftFrontMotor.configFactoryDefault();
|
||||||
|
|||||||
@@ -24,6 +24,8 @@ public class Drive extends SubsystemBase {
|
|||||||
// Put methods for controlling this subsystem
|
// Put methods for controlling this subsystem
|
||||||
// here. Call these from Commands.
|
// here. Call these from Commands.
|
||||||
|
|
||||||
|
private RobotTime m_robotTime = RobotTime.getInstance();
|
||||||
|
|
||||||
private WPI_TalonSRX m_leftFrontMotor;
|
private WPI_TalonSRX m_leftFrontMotor;
|
||||||
private WPI_TalonSRX m_rightFrontMotor;
|
private WPI_TalonSRX m_rightFrontMotor;
|
||||||
private WPI_TalonSRX m_leftBackMotor;
|
private WPI_TalonSRX m_leftBackMotor;
|
||||||
@@ -49,7 +51,7 @@ public class Drive extends SubsystemBase {
|
|||||||
public void periodic() {
|
public void periodic() {
|
||||||
m_gyro.updatePigeonDeltas();
|
m_gyro.updatePigeonDeltas();
|
||||||
|
|
||||||
if (RobotTime.m_frameNumber % DriveConstants.SMARTDASHBOARD_UPDATE_FRAME == 0) {
|
if (m_robotTime.m_frameNumber % DriveConstants.SMARTDASHBOARD_UPDATE_FRAME == 0) {
|
||||||
updateSmartDashboard();
|
updateSmartDashboard();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -18,6 +18,8 @@ import edu.wpi.first.wpiutil.math.MathUtil;
|
|||||||
* Gyro class that allows for interchangeable use between a pigeon and a navX
|
* Gyro class that allows for interchangeable use between a pigeon and a navX
|
||||||
*/
|
*/
|
||||||
public class RobotGyro extends GyroBase {
|
public class RobotGyro extends GyroBase {
|
||||||
|
private RobotTime m_robotTime = RobotTime.getInstance();
|
||||||
|
|
||||||
private PigeonIMU m_pigeon;
|
private PigeonIMU m_pigeon;
|
||||||
private AHRS m_navX;
|
private AHRS m_navX;
|
||||||
public boolean m_isGyroAPigeon; //true if pigeon, false if navX
|
public boolean m_isGyroAPigeon; //true if pigeon, false if navX
|
||||||
@@ -149,7 +151,7 @@ public class RobotGyro extends GyroBase {
|
|||||||
@Override
|
@Override
|
||||||
public double getRate() {
|
public double getRate() {
|
||||||
if (m_isGyroAPigeon) {
|
if (m_isGyroAPigeon) {
|
||||||
return m_deltaPigeonAngle / (RobotTime.m_deltaTime * 1000);
|
return m_deltaPigeonAngle / (m_robotTime.m_deltaTime * 1000);
|
||||||
} else {
|
} else {
|
||||||
return m_navX.getRate();
|
return m_navX.getRate();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -11,29 +11,42 @@ package frc4388.utility;
|
|||||||
* <p>Keeps track of Robot times like time passed, delta time, etc
|
* <p>Keeps track of Robot times like time passed, delta time, etc
|
||||||
* <p>All times are in milliseconds
|
* <p>All times are in milliseconds
|
||||||
*/
|
*/
|
||||||
public final class RobotTime {
|
public class RobotTime {
|
||||||
private static long m_currTime = System.currentTimeMillis();
|
private long m_currTime = System.currentTimeMillis();
|
||||||
public static long m_deltaTime = 0;
|
public long m_deltaTime = 0;
|
||||||
|
|
||||||
private static long m_startRobotTime = m_currTime;
|
private long m_startRobotTime = m_currTime;
|
||||||
public static long m_robotTime = 0;
|
public long m_robotTime = 0;
|
||||||
public static long m_lastRobotTime = 0;
|
public long m_lastRobotTime = 0;
|
||||||
|
|
||||||
private static long m_startMatchTime = 0;
|
private long m_startMatchTime = 0;
|
||||||
public static long m_matchTime = 0;
|
public long m_matchTime = 0;
|
||||||
public static long m_lastMatchTime = 0;
|
public long m_lastMatchTime = 0;
|
||||||
|
|
||||||
public static long m_frameNumber = 0;
|
public long m_frameNumber = 0;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* This class should not be instantiated.
|
* Private constructor prevents other classes from instantiating
|
||||||
*/
|
*/
|
||||||
private RobotTime(){}
|
private RobotTime(){}
|
||||||
|
|
||||||
|
private static RobotTime instance = null;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Gets the instance of Robot Time. If there is no instance running one will be created.
|
||||||
|
* @return instance of Robot Time
|
||||||
|
*/
|
||||||
|
public static RobotTime getInstance() {
|
||||||
|
if (instance == null) {
|
||||||
|
instance = new RobotTime();
|
||||||
|
}
|
||||||
|
return instance;
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Call this once per periodic loop.
|
* Call this once per periodic loop.
|
||||||
*/
|
*/
|
||||||
public static void updateTimes() {
|
public void updateTimes() {
|
||||||
m_lastRobotTime = m_robotTime;
|
m_lastRobotTime = m_robotTime;
|
||||||
m_lastMatchTime = m_matchTime;
|
m_lastMatchTime = m_matchTime;
|
||||||
|
|
||||||
@@ -50,7 +63,7 @@ public final class RobotTime {
|
|||||||
/**
|
/**
|
||||||
* Call this in both the auto and periodic inits
|
* Call this in both the auto and periodic inits
|
||||||
*/
|
*/
|
||||||
public static void startMatchTime() {
|
public void startMatchTime() {
|
||||||
if (m_matchTime == 0) {
|
if (m_matchTime == 0) {
|
||||||
m_startMatchTime = m_currTime;
|
m_startMatchTime = m_currTime;
|
||||||
m_matchTime = 1;
|
m_matchTime = 1;
|
||||||
@@ -60,7 +73,7 @@ public final class RobotTime {
|
|||||||
/**
|
/**
|
||||||
* Call this in disabled init
|
* Call this in disabled init
|
||||||
*/
|
*/
|
||||||
public static void endMatchTime() {
|
public void endMatchTime() {
|
||||||
m_startMatchTime = 0;
|
m_startMatchTime = 0;
|
||||||
m_matchTime = 0;
|
m_matchTime = 0;
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user