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.hal.FRCNetComm.tInstances; 010import edu.wpi.first.hal.FRCNetComm.tResourceType; 011import edu.wpi.first.hal.HAL; 012import edu.wpi.first.hal.HALUtil; 013import edu.wpi.first.math.MathShared; 014import edu.wpi.first.math.MathSharedStore; 015import edu.wpi.first.math.MathUsageId; 016import edu.wpi.first.networktables.MultiSubscriber; 017import edu.wpi.first.networktables.NetworkTableEvent; 018import edu.wpi.first.networktables.NetworkTableInstance; 019import edu.wpi.first.util.WPIUtilJNI; 020import edu.wpi.first.wpilibj.livewindow.LiveWindow; 021import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; 022import edu.wpi.first.wpilibj.util.WPILibVersion; 023import java.io.File; 024import java.io.IOException; 025import java.io.OutputStream; 026import java.nio.charset.StandardCharsets; 027import java.nio.file.Files; 028import java.util.concurrent.locks.ReentrantLock; 029import java.util.function.Supplier; 030 031/** 032 * Implement a Robot Program framework. The RobotBase class is intended to be subclassed to create a 033 * robot program. The user must implement {@link #startCompetition()}, which will be called once and 034 * is not expected to exit. The user must also implement {@link #endCompetition()}, which signals to 035 * the code in {@link #startCompetition()} that it should exit. 036 * 037 * <p>It is not recommended to subclass this class directly - instead subclass IterativeRobotBase or 038 * TimedRobot. 039 */ 040public abstract class RobotBase implements AutoCloseable { 041 /** The ID of the main Java thread. */ 042 // This is usually 1, but it is best to make sure 043 private static long m_threadId = -1; 044 045 private final MultiSubscriber m_suball; 046 047 private final int m_connListenerHandle; 048 049 private boolean m_dashboardDetected; 050 051 private static void setupCameraServerShared() { 052 CameraServerShared shared = 053 new CameraServerShared() { 054 @Override 055 public void reportVideoServer(int id) { 056 HAL.report(tResourceType.kResourceType_PCVideoServer, id + 1); 057 } 058 059 @Override 060 public void reportUsbCamera(int id) { 061 HAL.report(tResourceType.kResourceType_UsbCamera, id + 1); 062 } 063 064 @Override 065 public void reportDriverStationError(String error) { 066 DriverStation.reportError(error, true); 067 } 068 069 @Override 070 public void reportAxisCamera(int id) { 071 HAL.report(tResourceType.kResourceType_AxisCamera, id + 1); 072 } 073 074 @Override 075 public Long getRobotMainThreadId() { 076 return RobotBase.getMainThreadId(); 077 } 078 079 @Override 080 public boolean isRoboRIO() { 081 return !RobotBase.isSimulation(); 082 } 083 }; 084 085 CameraServerSharedStore.setCameraServerShared(shared); 086 } 087 088 private static void setupMathShared() { 089 MathSharedStore.setMathShared( 090 new MathShared() { 091 @Override 092 public void reportError(String error, StackTraceElement[] stackTrace) { 093 DriverStation.reportError(error, stackTrace); 094 } 095 096 @Override 097 public void reportUsage(MathUsageId id, int count) { 098 switch (id) { 099 case kKinematics_DifferentialDrive -> 100 HAL.report( 101 tResourceType.kResourceType_Kinematics, 102 tInstances.kKinematics_DifferentialDrive); 103 case kKinematics_MecanumDrive -> 104 HAL.report( 105 tResourceType.kResourceType_Kinematics, tInstances.kKinematics_MecanumDrive); 106 case kKinematics_SwerveDrive -> 107 HAL.report( 108 tResourceType.kResourceType_Kinematics, tInstances.kKinematics_SwerveDrive); 109 case kTrajectory_TrapezoidProfile -> 110 HAL.report(tResourceType.kResourceType_TrapezoidProfile, count); 111 case kFilter_Linear -> HAL.report(tResourceType.kResourceType_LinearFilter, count); 112 case kOdometry_DifferentialDrive -> 113 HAL.report( 114 tResourceType.kResourceType_Odometry, tInstances.kOdometry_DifferentialDrive); 115 case kOdometry_SwerveDrive -> 116 HAL.report( 117 tResourceType.kResourceType_Odometry, tInstances.kOdometry_SwerveDrive); 118 case kOdometry_MecanumDrive -> 119 HAL.report( 120 tResourceType.kResourceType_Odometry, tInstances.kOdometry_MecanumDrive); 121 case kController_PIDController2 -> 122 HAL.report(tResourceType.kResourceType_PIDController2, count); 123 case kController_ProfiledPIDController -> 124 HAL.report(tResourceType.kResourceType_ProfiledPIDController, count); 125 case kController_BangBangController -> 126 HAL.report(tResourceType.kResourceType_BangBangController, count); 127 case kTrajectory_PathWeaver -> 128 HAL.report(tResourceType.kResourceType_PathWeaverTrajectory, count); 129 case kController_LinearQuadraticRegulator -> 130 HAL.report(tResourceType.kResourceType_LinearQuadraticRegulator, count); 131 case kEstimator_KalmanFilter -> 132 HAL.report(tResourceType.kResourceType_KalmanFilter, count); 133 case kEstimator_PoseEstimator -> 134 HAL.report(tResourceType.kResourceType_PoseEstimator, count); 135 case kEstimator_PoseEstimator3d -> 136 HAL.report(tResourceType.kResourceType_PoseEstimator3d, count); 137 case kSystem_LinearSystemLoop -> 138 HAL.report(tResourceType.kResourceType_LinearSystemLoop, count); 139 default -> { 140 // NOP 141 } 142 } 143 } 144 145 @Override 146 public double getTimestamp() { 147 return Timer.getTimestamp(); 148 } 149 }); 150 } 151 152 /** 153 * Constructor for a generic robot program. User code can be placed in the constructor that runs 154 * before the Autonomous or Operator Control period starts. The constructor will run to completion 155 * before Autonomous is entered. 156 * 157 * <p>This must be used to ensure that the communications code starts. In the future it would be 158 * nice to put this code into its own task that loads on boot so ensure that it runs. 159 */ 160 protected RobotBase() { 161 final NetworkTableInstance inst = NetworkTableInstance.getDefault(); 162 m_threadId = Thread.currentThread().getId(); 163 setupCameraServerShared(); 164 setupMathShared(); 165 // subscribe to "" to force persistent values to propagate to local 166 m_suball = new MultiSubscriber(inst, new String[] {""}); 167 if (!isSimulation()) { 168 inst.startServer("/home/lvuser/networktables.json"); 169 } else { 170 inst.startServer(); 171 } 172 173 // wait for the NT server to actually start 174 try { 175 int count = 0; 176 while (inst.getNetworkMode().contains(NetworkTableInstance.NetworkMode.kStarting)) { 177 Thread.sleep(10); 178 count++; 179 if (count > 100) { 180 throw new InterruptedException(); 181 } 182 } 183 } catch (InterruptedException ex) { 184 System.err.println("timed out while waiting for NT server to start"); 185 } 186 187 m_connListenerHandle = 188 inst.addConnectionListener( 189 false, 190 event -> { 191 if (event.is(NetworkTableEvent.Kind.kConnected)) { 192 if (event.connInfo.remote_id.startsWith("glass")) { 193 HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Glass); 194 m_dashboardDetected = true; 195 } else if (event.connInfo.remote_id.startsWith("SmartDashboard")) { 196 HAL.report( 197 tResourceType.kResourceType_Dashboard, tInstances.kDashboard_SmartDashboard); 198 m_dashboardDetected = true; 199 } else if (event.connInfo.remote_id.startsWith("shuffleboard")) { 200 HAL.report( 201 tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Shuffleboard); 202 m_dashboardDetected = true; 203 } else if (event.connInfo.remote_id.startsWith("elastic") 204 || event.connInfo.remote_id.startsWith("Elastic")) { 205 HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Elastic); 206 m_dashboardDetected = true; 207 } else if (event.connInfo.remote_id.startsWith("Dashboard")) { 208 HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_LabVIEW); 209 m_dashboardDetected = true; 210 } else if (event.connInfo.remote_id.startsWith("AdvantageScope")) { 211 HAL.report( 212 tResourceType.kResourceType_Dashboard, tInstances.kDashboard_AdvantageScope); 213 m_dashboardDetected = true; 214 } else if (event.connInfo.remote_id.startsWith("QDash") 215 || event.connInfo.remote_id.startsWith("QFRCDashboard")) { 216 HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_QDash); 217 m_dashboardDetected = true; 218 } else if (event.connInfo.remote_id.startsWith("FRC Web Components")) { 219 HAL.report( 220 tResourceType.kResourceType_Dashboard, 221 tInstances.kDashboard_FRCWebComponents); 222 m_dashboardDetected = true; 223 } else { 224 // Only report unknown if there wasn't another dashboard already reported 225 // (unknown could also be another device) 226 if (!m_dashboardDetected) { 227 int delim = event.connInfo.remote_id.indexOf('@'); 228 if (delim != -1) { 229 HAL.report( 230 tResourceType.kResourceType_Dashboard, 231 tInstances.kDashboard_Unknown, 232 0, 233 event.connInfo.remote_id.substring(0, delim)); 234 } else { 235 HAL.report( 236 tResourceType.kResourceType_Dashboard, 237 tInstances.kDashboard_Unknown, 238 0, 239 event.connInfo.remote_id); 240 } 241 } 242 } 243 } 244 }); 245 246 LiveWindow.setEnabled(false); 247 Shuffleboard.disableActuatorWidgets(); 248 } 249 250 /** 251 * Returns the main thread ID. 252 * 253 * @return The main thread ID. 254 */ 255 public static long getMainThreadId() { 256 return m_threadId; 257 } 258 259 @Override 260 public void close() { 261 m_suball.close(); 262 NetworkTableInstance.getDefault().removeListener(m_connListenerHandle); 263 } 264 265 /** 266 * Get the current runtime type. 267 * 268 * @return Current runtime type. 269 */ 270 public static RuntimeType getRuntimeType() { 271 return RuntimeType.getValue(HALUtil.getHALRuntimeType()); 272 } 273 274 /** 275 * Get if the robot is a simulation. 276 * 277 * @return If the robot is running in simulation. 278 */ 279 public static boolean isSimulation() { 280 return getRuntimeType() == RuntimeType.kSimulation; 281 } 282 283 /** 284 * Get if the robot is real. 285 * 286 * @return If the robot is running in the real world. 287 */ 288 public static boolean isReal() { 289 RuntimeType runtimeType = getRuntimeType(); 290 return runtimeType == RuntimeType.kRoboRIO || runtimeType == RuntimeType.kRoboRIO2; 291 } 292 293 /** 294 * Determine if the Robot is currently disabled. 295 * 296 * @return True if the Robot is currently disabled by the Driver Station. 297 */ 298 public boolean isDisabled() { 299 return DriverStation.isDisabled(); 300 } 301 302 /** 303 * Determine if the Robot is currently enabled. 304 * 305 * @return True if the Robot is currently enabled by the Driver Station. 306 */ 307 public boolean isEnabled() { 308 return DriverStation.isEnabled(); 309 } 310 311 /** 312 * Determine if the robot is currently in Autonomous mode as determined by the Driver Station. 313 * 314 * @return True if the robot is currently operating Autonomously. 315 */ 316 public boolean isAutonomous() { 317 return DriverStation.isAutonomous(); 318 } 319 320 /** 321 * Determine if the robot is currently in Autonomous mode and enabled as determined by the Driver 322 * Station. 323 * 324 * @return True if the robot is currently operating autonomously while enabled. 325 */ 326 public boolean isAutonomousEnabled() { 327 return DriverStation.isAutonomousEnabled(); 328 } 329 330 /** 331 * Determine if the robot is currently in Test mode as determined by the Driver Station. 332 * 333 * @return True if the robot is currently operating in Test mode. 334 */ 335 public boolean isTest() { 336 return DriverStation.isTest(); 337 } 338 339 /** 340 * Determine if the robot is current in Test mode and enabled as determined by the Driver Station. 341 * 342 * @return True if the robot is currently operating in Test mode while enabled. 343 */ 344 public boolean isTestEnabled() { 345 return DriverStation.isTestEnabled(); 346 } 347 348 /** 349 * Determine if the robot is currently in Operator Control mode as determined by the Driver 350 * Station. 351 * 352 * @return True if the robot is currently operating in Tele-Op mode. 353 */ 354 public boolean isTeleop() { 355 return DriverStation.isTeleop(); 356 } 357 358 /** 359 * Determine if the robot is currently in Operator Control mode and enabled as determined by the 360 * Driver Station. 361 * 362 * @return True if the robot is currently operating in Tele-Op mode while enabled. 363 */ 364 public boolean isTeleopEnabled() { 365 return DriverStation.isTeleopEnabled(); 366 } 367 368 /** 369 * Start the main robot code. This function will be called once and should not exit until 370 * signalled by {@link #endCompetition()} 371 */ 372 public abstract void startCompetition(); 373 374 /** Ends the main loop in {@link #startCompetition()}. */ 375 public abstract void endCompetition(); 376 377 private static final ReentrantLock m_runMutex = new ReentrantLock(); 378 private static RobotBase m_robotCopy; 379 private static boolean m_suppressExitWarning; 380 381 /** Run the robot main loop. */ 382 private static <T extends RobotBase> void runRobot(Supplier<T> robotSupplier) { 383 System.out.println("********** Robot program starting **********"); 384 385 T robot; 386 try { 387 robot = robotSupplier.get(); 388 } catch (Throwable throwable) { 389 Throwable cause = throwable.getCause(); 390 if (cause != null) { 391 throwable = cause; 392 } 393 String robotName = "Unknown"; 394 StackTraceElement[] elements = throwable.getStackTrace(); 395 if (elements.length > 0) { 396 robotName = elements[0].getClassName(); 397 } 398 DriverStation.reportError( 399 "Unhandled exception instantiating robot " + robotName + " " + throwable, elements); 400 DriverStation.reportError( 401 "The robot program quit unexpectedly." 402 + " This is usually due to a code error.\n" 403 + " The above stacktrace can help determine where the error occurred.\n" 404 + " See https://wpilib.org/stacktrace for more information.\n", 405 false); 406 DriverStation.reportError("Could not instantiate robot " + robotName + "!", false); 407 return; 408 } 409 410 m_runMutex.lock(); 411 m_robotCopy = robot; 412 m_runMutex.unlock(); 413 414 if (!isSimulation()) { 415 final File file = new File("/tmp/frc_versions/FRC_Lib_Version.ini"); 416 try { 417 if (file.exists() && !file.delete()) { 418 throw new IOException("Failed to delete FRC_Lib_Version.ini"); 419 } 420 421 if (!file.createNewFile()) { 422 throw new IOException("Failed to create new FRC_Lib_Version.ini"); 423 } 424 425 try (OutputStream output = Files.newOutputStream(file.toPath())) { 426 output.write("Java ".getBytes(StandardCharsets.UTF_8)); 427 output.write(WPILibVersion.Version.getBytes(StandardCharsets.UTF_8)); 428 } 429 } catch (IOException ex) { 430 DriverStation.reportError("Could not write FRC_Lib_Version.ini: " + ex, ex.getStackTrace()); 431 } 432 } 433 434 boolean errorOnExit = false; 435 try { 436 robot.startCompetition(); 437 } catch (Throwable throwable) { 438 Throwable cause = throwable.getCause(); 439 if (cause != null) { 440 throwable = cause; 441 } 442 DriverStation.reportError("Unhandled exception: " + throwable, throwable.getStackTrace()); 443 errorOnExit = true; 444 } finally { 445 m_runMutex.lock(); 446 boolean suppressExitWarning = m_suppressExitWarning; 447 m_runMutex.unlock(); 448 if (!suppressExitWarning) { 449 // startCompetition never returns unless exception occurs.... 450 DriverStation.reportWarning( 451 "The robot program quit unexpectedly." 452 + " This is usually due to a code error.\n" 453 + " The above stacktrace can help determine where the error occurred.\n" 454 + " See https://wpilib.org/stacktrace for more information.", 455 false); 456 if (errorOnExit) { 457 DriverStation.reportError( 458 "The startCompetition() method (or methods called by it) should have " 459 + "handled the exception above.", 460 false); 461 } else { 462 DriverStation.reportError("Unexpected return from startCompetition() method.", false); 463 } 464 } 465 } 466 } 467 468 /** 469 * Suppress the "The robot program quit unexpectedly." message. 470 * 471 * @param value True if exit warning should be suppressed. 472 */ 473 public static void suppressExitWarning(boolean value) { 474 m_runMutex.lock(); 475 m_suppressExitWarning = value; 476 m_runMutex.unlock(); 477 } 478 479 /** 480 * Starting point for the applications. 481 * 482 * @param <T> Robot subclass. 483 * @param robotSupplier Function that returns an instance of the robot subclass. 484 */ 485 public static <T extends RobotBase> void startRobot(Supplier<T> robotSupplier) { 486 // Check that the MSVC runtime is valid. 487 WPIUtilJNI.checkMsvcRuntime(); 488 489 if (!HAL.initialize(500, 0)) { 490 throw new IllegalStateException("Failed to initialize. Terminating"); 491 } 492 493 // Force refresh DS data 494 DriverStation.refreshData(); 495 496 HAL.report( 497 tResourceType.kResourceType_Language, tInstances.kLanguage_Java, 0, WPILibVersion.Version); 498 499 if (!Notifier.setHALThreadPriority(true, 40)) { 500 DriverStation.reportWarning("Setting HAL Notifier RT priority to 40 failed", false); 501 } 502 503 if (HAL.hasMain()) { 504 Thread thread = 505 new Thread( 506 () -> { 507 runRobot(robotSupplier); 508 HAL.exitMain(); 509 }, 510 "robot main"); 511 thread.setDaemon(true); 512 thread.start(); 513 HAL.runMain(); 514 suppressExitWarning(true); 515 m_runMutex.lock(); 516 RobotBase robot = m_robotCopy; 517 m_runMutex.unlock(); 518 if (robot != null) { 519 robot.endCompetition(); 520 } 521 try { 522 thread.join(1000); 523 } catch (InterruptedException ex) { 524 Thread.currentThread().interrupt(); 525 } 526 } else { 527 runRobot(robotSupplier); 528 } 529 530 // On RIO, this will just terminate rather than shutting down cleanly (it's a no-op in sim). 531 // It's not worth the risk of hanging on shutdown when we want the code to restart as quickly 532 // as possible. 533 HAL.terminate(); 534 535 HAL.shutdown(); 536 537 System.exit(0); 538 } 539}