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.cameraserver.CameraServerShared; 008import edu.wpi.first.cameraserver.CameraServerSharedStore; 009import edu.wpi.first.cscore.CameraServerJNI; 010import edu.wpi.first.hal.FRCNetComm.tInstances; 011import edu.wpi.first.hal.FRCNetComm.tResourceType; 012import edu.wpi.first.hal.HAL; 013import edu.wpi.first.hal.HALUtil; 014import edu.wpi.first.math.MathShared; 015import edu.wpi.first.math.MathSharedStore; 016import edu.wpi.first.math.MathUsageId; 017import edu.wpi.first.networktables.NetworkTableInstance; 018import edu.wpi.first.wpilibj.livewindow.LiveWindow; 019import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; 020import edu.wpi.first.wpilibj.util.WPILibVersion; 021import java.io.File; 022import java.io.IOException; 023import java.io.OutputStream; 024import java.nio.charset.StandardCharsets; 025import java.nio.file.Files; 026import java.util.concurrent.locks.ReentrantLock; 027import java.util.function.Supplier; 028 029/** 030 * Implement a Robot Program framework. The RobotBase class is intended to be subclassed by a user 031 * creating a robot program. Overridden autonomous() and operatorControl() methods are called at the 032 * appropriate time as the match proceeds. In the current implementation, the Autonomous code will 033 * run to completion before the OperatorControl code could start. In the future the Autonomous code 034 * might be spawned as a task, then killed at the end of the Autonomous period. 035 */ 036public abstract class RobotBase implements AutoCloseable { 037 /** The ID of the main Java thread. */ 038 // This is usually 1, but it is best to make sure 039 private static long m_threadId = -1; 040 041 private static void setupCameraServerShared() { 042 CameraServerShared shared = 043 new CameraServerShared() { 044 @Override 045 public void reportVideoServer(int id) { 046 HAL.report(tResourceType.kResourceType_PCVideoServer, id + 1); 047 } 048 049 @Override 050 public void reportUsbCamera(int id) { 051 HAL.report(tResourceType.kResourceType_UsbCamera, id + 1); 052 } 053 054 @Override 055 public void reportDriverStationError(String error) { 056 DriverStation.reportError(error, true); 057 } 058 059 @Override 060 public void reportAxisCamera(int id) { 061 HAL.report(tResourceType.kResourceType_AxisCamera, id + 1); 062 } 063 064 @Override 065 public Long getRobotMainThreadId() { 066 return RobotBase.getMainThreadId(); 067 } 068 069 @Override 070 public boolean isRoboRIO() { 071 return RobotBase.isReal(); 072 } 073 }; 074 075 CameraServerSharedStore.setCameraServerShared(shared); 076 } 077 078 private static void setupMathShared() { 079 MathSharedStore.setMathShared( 080 new MathShared() { 081 @Override 082 public void reportError(String error, StackTraceElement[] stackTrace) { 083 DriverStation.reportError(error, stackTrace); 084 } 085 086 @Override 087 public void reportUsage(MathUsageId id, int count) { 088 switch (id) { 089 case kKinematics_DifferentialDrive: 090 HAL.report( 091 tResourceType.kResourceType_Kinematics, 092 tInstances.kKinematics_DifferentialDrive); 093 break; 094 case kKinematics_MecanumDrive: 095 HAL.report( 096 tResourceType.kResourceType_Kinematics, tInstances.kKinematics_MecanumDrive); 097 break; 098 case kKinematics_SwerveDrive: 099 HAL.report( 100 tResourceType.kResourceType_Kinematics, tInstances.kKinematics_SwerveDrive); 101 break; 102 case kTrajectory_TrapezoidProfile: 103 HAL.report(tResourceType.kResourceType_TrapezoidProfile, count); 104 break; 105 case kFilter_Linear: 106 HAL.report(tResourceType.kResourceType_LinearFilter, count); 107 break; 108 case kOdometry_DifferentialDrive: 109 HAL.report( 110 tResourceType.kResourceType_Odometry, tInstances.kOdometry_DifferentialDrive); 111 break; 112 case kOdometry_SwerveDrive: 113 HAL.report(tResourceType.kResourceType_Odometry, tInstances.kOdometry_SwerveDrive); 114 break; 115 case kOdometry_MecanumDrive: 116 HAL.report(tResourceType.kResourceType_Odometry, tInstances.kOdometry_MecanumDrive); 117 break; 118 case kController_PIDController2: 119 HAL.report(tResourceType.kResourceType_PIDController2, count); 120 break; 121 case kController_ProfiledPIDController: 122 HAL.report(tResourceType.kResourceType_ProfiledPIDController, count); 123 break; 124 default: 125 break; 126 } 127 } 128 }); 129 } 130 131 /** 132 * Constructor for a generic robot program. User code should be placed in the constructor that 133 * runs before the Autonomous or Operator Control period starts. The constructor will run to 134 * completion before Autonomous is entered. 135 * 136 * <p>This must be used to ensure that the communications code starts. In the future it would be 137 * nice to put this code into it's own task that loads on boot so ensure that it runs. 138 */ 139 protected RobotBase() { 140 final NetworkTableInstance inst = NetworkTableInstance.getDefault(); 141 m_threadId = Thread.currentThread().getId(); 142 setupCameraServerShared(); 143 setupMathShared(); 144 inst.setNetworkIdentity("Robot"); 145 if (isReal()) { 146 inst.startServer("/home/lvuser/networktables.ini"); 147 } else { 148 inst.startServer(); 149 } 150 inst.getTable("LiveWindow").getSubTable(".status").getEntry("LW Enabled").setBoolean(false); 151 152 LiveWindow.setEnabled(false); 153 Shuffleboard.disableActuatorWidgets(); 154 } 155 156 public static long getMainThreadId() { 157 return m_threadId; 158 } 159 160 @Override 161 public void close() {} 162 163 /** 164 * Get the current runtime type. 165 * 166 * @return Current runtime type. 167 */ 168 public static RuntimeType getRuntimeType() { 169 return RuntimeType.getValue(HALUtil.getHALRuntimeType()); 170 } 171 172 /** 173 * Get if the robot is a simulation. 174 * 175 * @return If the robot is running in simulation. 176 */ 177 public static boolean isSimulation() { 178 return !isReal(); 179 } 180 181 /** 182 * Get if the robot is real. 183 * 184 * @return If the robot is running in the real world. 185 */ 186 public static boolean isReal() { 187 RuntimeType runtimeType = getRuntimeType(); 188 return runtimeType == RuntimeType.kRoboRIO || runtimeType == RuntimeType.kRoboRIO2; 189 } 190 191 /** 192 * Determine if the Robot is currently disabled. 193 * 194 * @return True if the Robot is currently disabled by the field controls. 195 */ 196 public boolean isDisabled() { 197 return DriverStation.isDisabled(); 198 } 199 200 /** 201 * Determine if the Robot is currently enabled. 202 * 203 * @return True if the Robot is currently enabled by the field controls. 204 */ 205 public boolean isEnabled() { 206 return DriverStation.isEnabled(); 207 } 208 209 /** 210 * Determine if the robot is currently in Autonomous mode as determined by the field controls. 211 * 212 * @return True if the robot is currently operating Autonomously. 213 */ 214 public boolean isAutonomous() { 215 return DriverStation.isAutonomous(); 216 } 217 218 /** 219 * Determine if the robot is current in Autonomous mode and enabled as determined by the field 220 * controls. 221 * 222 * @return True if the robot is currently operating autonomously while enabled. 223 */ 224 public boolean isAutonomousEnabled() { 225 return DriverStation.isAutonomousEnabled(); 226 } 227 228 /** 229 * Determine if the robot is currently in Test mode as determined by the driver station. 230 * 231 * @return True if the robot is currently operating in Test mode. 232 */ 233 public boolean isTest() { 234 return DriverStation.isTest(); 235 } 236 237 /** 238 * Determine if the robot is currently in Operator Control mode as determined by the field 239 * controls. 240 * 241 * @return True if the robot is currently operating in Tele-Op mode. 242 * @deprecated Use isTeleop() instead. 243 */ 244 @Deprecated(since = "2022", forRemoval = true) 245 public boolean isOperatorControl() { 246 return DriverStation.isTeleop(); 247 } 248 249 /** 250 * Determine if the robot is currently in Operator Control mode as determined by the field 251 * controls. 252 * 253 * @return True if the robot is currently operating in Tele-Op mode. 254 */ 255 public boolean isTeleop() { 256 return DriverStation.isTeleop(); 257 } 258 259 /** 260 * Determine if the robot is current in Operator Control mode and enabled as determined by the 261 * field controls. 262 * 263 * @return True if the robot is currently operating in Tele-Op mode while enabled. 264 * @deprecated Use isTeleopEnabled() instead. 265 */ 266 @Deprecated(since = "2022", forRemoval = true) 267 public boolean isOperatorControlEnabled() { 268 return DriverStation.isTeleopEnabled(); 269 } 270 271 /** 272 * Determine if the robot is current in Operator Control mode and enabled as determined by the 273 * field controls. 274 * 275 * @return True if the robot is currently operating in Tele-Op mode while enabled. 276 */ 277 public boolean isTeleopEnabled() { 278 return DriverStation.isTeleopEnabled(); 279 } 280 281 /** 282 * Indicates if new data is available from the driver station. 283 * 284 * @return Has new data arrived over the network since the last time this function was called? 285 */ 286 public boolean isNewDataAvailable() { 287 return DriverStation.isNewControlData(); 288 } 289 290 /** Provide an alternate "main loop" via startCompetition(). */ 291 public abstract void startCompetition(); 292 293 /** Ends the main loop in startCompetition(). */ 294 public abstract void endCompetition(); 295 296 @SuppressWarnings("MissingJavadocMethod") 297 public static boolean getBooleanProperty(String name, boolean defaultValue) { 298 String propVal = System.getProperty(name); 299 if (propVal == null) { 300 return defaultValue; 301 } 302 if ("false".equalsIgnoreCase(propVal)) { 303 return false; 304 } else if ("true".equalsIgnoreCase(propVal)) { 305 return true; 306 } else { 307 throw new IllegalStateException(propVal); 308 } 309 } 310 311 private static final ReentrantLock m_runMutex = new ReentrantLock(); 312 private static RobotBase m_robotCopy; 313 private static boolean m_suppressExitWarning; 314 315 /** Run the robot main loop. */ 316 @SuppressWarnings({"PMD.AvoidCatchingThrowable", "PMD.AvoidReassigningCatchVariables"}) 317 private static <T extends RobotBase> void runRobot(Supplier<T> robotSupplier) { 318 System.out.println("********** Robot program starting **********"); 319 320 T robot; 321 try { 322 robot = robotSupplier.get(); 323 } catch (Throwable throwable) { 324 Throwable cause = throwable.getCause(); 325 if (cause != null) { 326 throwable = cause; 327 } 328 String robotName = "Unknown"; 329 StackTraceElement[] elements = throwable.getStackTrace(); 330 if (elements.length > 0) { 331 robotName = elements[0].getClassName(); 332 } 333 DriverStation.reportError( 334 "Unhandled exception instantiating robot " + robotName + " " + throwable.toString(), 335 elements); 336 DriverStation.reportError( 337 "The robot program quit unexpectedly." 338 + " This is usually due to a code error.\n" 339 + " The above stacktrace can help determine where the error occurred.\n" 340 + " See https://wpilib.org/stacktrace for more information.\n", 341 false); 342 DriverStation.reportError("Could not instantiate robot " + robotName + "!", false); 343 return; 344 } 345 346 m_runMutex.lock(); 347 m_robotCopy = robot; 348 m_runMutex.unlock(); 349 350 if (isReal()) { 351 final File file = new File("/tmp/frc_versions/FRC_Lib_Version.ini"); 352 try { 353 if (file.exists() && !file.delete()) { 354 throw new IOException("Failed to delete FRC_Lib_Version.ini"); 355 } 356 357 if (!file.createNewFile()) { 358 throw new IOException("Failed to create new FRC_Lib_Version.ini"); 359 } 360 361 try (OutputStream output = Files.newOutputStream(file.toPath())) { 362 output.write("Java ".getBytes(StandardCharsets.UTF_8)); 363 output.write(WPILibVersion.Version.getBytes(StandardCharsets.UTF_8)); 364 } 365 } catch (IOException ex) { 366 DriverStation.reportError( 367 "Could not write FRC_Lib_Version.ini: " + ex.toString(), ex.getStackTrace()); 368 } 369 } 370 371 boolean errorOnExit = false; 372 try { 373 robot.startCompetition(); 374 } catch (Throwable throwable) { 375 Throwable cause = throwable.getCause(); 376 if (cause != null) { 377 throwable = cause; 378 } 379 DriverStation.reportError( 380 "Unhandled exception: " + throwable.toString(), throwable.getStackTrace()); 381 errorOnExit = true; 382 } finally { 383 m_runMutex.lock(); 384 boolean suppressExitWarning = m_suppressExitWarning; 385 m_runMutex.unlock(); 386 if (!suppressExitWarning) { 387 // startCompetition never returns unless exception occurs.... 388 DriverStation.reportWarning( 389 "The robot program quit unexpectedly." 390 + " This is usually due to a code error.\n" 391 + " The above stacktrace can help determine where the error occurred.\n" 392 + " See https://wpilib.org/stacktrace for more information.", 393 false); 394 if (errorOnExit) { 395 DriverStation.reportError( 396 "The startCompetition() method (or methods called by it) should have " 397 + "handled the exception above.", 398 false); 399 } else { 400 DriverStation.reportError("Unexpected return from startCompetition() method.", false); 401 } 402 } 403 } 404 } 405 406 /** 407 * Suppress the "The robot program quit unexpectedly." message. 408 * 409 * @param value True if exit warning should be suppressed. 410 */ 411 public static void suppressExitWarning(boolean value) { 412 m_runMutex.lock(); 413 m_suppressExitWarning = value; 414 m_runMutex.unlock(); 415 } 416 417 /** 418 * Starting point for the applications. 419 * 420 * @param <T> Robot subclass. 421 * @param robotSupplier Function that returns an instance of the robot subclass. 422 */ 423 public static <T extends RobotBase> void startRobot(Supplier<T> robotSupplier) { 424 if (!HAL.initialize(500, 0)) { 425 throw new IllegalStateException("Failed to initialize. Terminating"); 426 } 427 428 // Call a CameraServer JNI function to force OpenCV native library loading 429 // Needed because all the OpenCV JNI functions don't have built in loading 430 CameraServerJNI.enumerateSinks(); 431 432 HAL.report( 433 tResourceType.kResourceType_Language, tInstances.kLanguage_Java, 0, WPILibVersion.Version); 434 435 if (!Notifier.setHALThreadPriority(true, 40)) { 436 DriverStation.reportWarning("Setting HAL Notifier RT priority to 40 failed", false); 437 } 438 439 if (HAL.hasMain()) { 440 Thread thread = 441 new Thread( 442 () -> { 443 runRobot(robotSupplier); 444 HAL.exitMain(); 445 }, 446 "robot main"); 447 thread.setDaemon(true); 448 thread.start(); 449 HAL.runMain(); 450 suppressExitWarning(true); 451 m_runMutex.lock(); 452 RobotBase robot = m_robotCopy; 453 m_runMutex.unlock(); 454 if (robot != null) { 455 robot.endCompetition(); 456 } 457 try { 458 thread.join(1000); 459 } catch (InterruptedException ex) { 460 Thread.currentThread().interrupt(); 461 } 462 } else { 463 runRobot(robotSupplier); 464 } 465 466 HAL.shutdown(); 467 468 System.exit(0); 469 } 470}