001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj; 006 007import edu.wpi.first.hal.FRCNetComm.tInstances; 008import edu.wpi.first.hal.FRCNetComm.tResourceType; 009import edu.wpi.first.hal.HAL; 010import edu.wpi.first.hal.NotifierJNI; 011import java.util.PriorityQueue; 012 013/** 014 * TimedRobot implements the IterativeRobotBase robot program framework. 015 * 016 * <p>The TimedRobot class is intended to be subclassed by a user creating a robot program. 017 * 018 * <p>periodic() functions from the base class are called on an interval by a Notifier instance. 019 */ 020public class TimedRobot extends IterativeRobotBase { 021 @SuppressWarnings("MemberName") 022 static class Callback implements Comparable<Callback> { 023 public Runnable func; 024 public double period; 025 public double expirationTime; 026 027 /** 028 * Construct a callback container. 029 * 030 * @param func The callback to run. 031 * @param startTimeSeconds The common starting point for all callback scheduling in seconds. 032 * @param periodSeconds The period at which to run the callback in seconds. 033 * @param offsetSeconds The offset from the common starting time in seconds. 034 */ 035 Callback(Runnable func, double startTimeSeconds, double periodSeconds, double offsetSeconds) { 036 this.func = func; 037 this.period = periodSeconds; 038 this.expirationTime = 039 startTimeSeconds 040 + offsetSeconds 041 + Math.floor((Timer.getFPGATimestamp() - startTimeSeconds) / this.period) 042 * this.period 043 + this.period; 044 } 045 046 @Override 047 public boolean equals(Object rhs) { 048 if (rhs instanceof Callback) { 049 return Double.compare(expirationTime, ((Callback) rhs).expirationTime) == 0; 050 } 051 return false; 052 } 053 054 @Override 055 public int hashCode() { 056 return Double.hashCode(expirationTime); 057 } 058 059 @Override 060 public int compareTo(Callback rhs) { 061 // Elements with sooner expiration times are sorted as lesser. The head of 062 // Java's PriorityQueue is the least element. 063 return Double.compare(expirationTime, rhs.expirationTime); 064 } 065 } 066 067 public static final double kDefaultPeriod = 0.02; 068 069 // The C pointer to the notifier object. We don't use it directly, it is 070 // just passed to the JNI bindings. 071 private final int m_notifier = NotifierJNI.initializeNotifier(); 072 073 private double m_startTime; 074 075 private final PriorityQueue<Callback> m_callbacks = new PriorityQueue<>(); 076 077 /** Constructor for TimedRobot. */ 078 protected TimedRobot() { 079 this(kDefaultPeriod); 080 } 081 082 /** 083 * Constructor for TimedRobot. 084 * 085 * @param period Period in seconds. 086 */ 087 protected TimedRobot(double period) { 088 super(period); 089 m_startTime = Timer.getFPGATimestamp(); 090 addPeriodic(this::loopFunc, period); 091 NotifierJNI.setNotifierName(m_notifier, "TimedRobot"); 092 093 HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Timed); 094 } 095 096 @Override 097 @SuppressWarnings("NoFinalizer") 098 protected void finalize() { 099 NotifierJNI.stopNotifier(m_notifier); 100 NotifierJNI.cleanNotifier(m_notifier); 101 } 102 103 /** Provide an alternate "main loop" via startCompetition(). */ 104 @Override 105 @SuppressWarnings("UnsafeFinalization") 106 public void startCompetition() { 107 robotInit(); 108 109 if (isSimulation()) { 110 simulationInit(); 111 } 112 113 // Tell the DS that the robot is ready to be enabled 114 System.out.println("********** Robot program startup complete **********"); 115 HAL.observeUserProgramStarting(); 116 117 // Loop forever, calling the appropriate mode-dependent function 118 while (true) { 119 // We don't have to check there's an element in the queue first because 120 // there's always at least one (the constructor adds one). It's reenqueued 121 // at the end of the loop. 122 var callback = m_callbacks.poll(); 123 124 NotifierJNI.updateNotifierAlarm(m_notifier, (long) (callback.expirationTime * 1e6)); 125 126 long curTime = NotifierJNI.waitForNotifierAlarm(m_notifier); 127 if (curTime == 0) { 128 break; 129 } 130 131 callback.func.run(); 132 133 callback.expirationTime += callback.period; 134 m_callbacks.add(callback); 135 136 // Process all other callbacks that are ready to run 137 while ((long) (m_callbacks.peek().expirationTime * 1e6) <= curTime) { 138 callback = m_callbacks.poll(); 139 140 callback.func.run(); 141 142 callback.expirationTime += callback.period; 143 m_callbacks.add(callback); 144 } 145 } 146 } 147 148 /** Ends the main loop in startCompetition(). */ 149 @Override 150 public void endCompetition() { 151 NotifierJNI.stopNotifier(m_notifier); 152 } 153 154 /** 155 * Add a callback to run at a specific period. 156 * 157 * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run 158 * synchronously. Interactions between them are thread-safe. 159 * 160 * @param callback The callback to run. 161 * @param periodSeconds The period at which to run the callback in seconds. 162 */ 163 public void addPeriodic(Runnable callback, double periodSeconds) { 164 m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, 0.0)); 165 } 166 167 /** 168 * Add a callback to run at a specific period with a starting time offset. 169 * 170 * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run 171 * synchronously. Interactions between them are thread-safe. 172 * 173 * @param callback The callback to run. 174 * @param periodSeconds The period at which to run the callback in seconds. 175 * @param offsetSeconds The offset from the common starting time in seconds. This is useful for 176 * scheduling a callback in a different timeslot relative to TimedRobot. 177 */ 178 public void addPeriodic(Runnable callback, double periodSeconds, double offsetSeconds) { 179 m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, offsetSeconds)); 180 } 181}