Package frclib.robotcore
Class FrcRobotBase
java.lang.Object
edu.wpi.first.wpilibj.RobotBase
frclib.robotcore.FrcRobotBase
- All Implemented Interfaces:
AutoCloseable
public abstract class FrcRobotBase
extends edu.wpi.first.wpilibj.RobotBase
This class defines and implements the FrcRobotBase object. The FrcRobotBase object implements a cooperative
multitasking robot. Different subsystems register themselves as CoopTasks. FrcRobotBase uses the TaskMgr to
task switch between different subsystem tasks at various points in the robot loop. This basically simulates
a cooperative multitasking scheduler that task switches between them in different modes.
-
Constructor Summary
ConstructorsConstructorDescriptionFrcRobotBase
(String robotName) Constructor: Create an instance of the object. -
Method Summary
Modifier and TypeMethodDescriptionvoid
Called to end the competition loop.This method returns the Autonomous robot mode object.boolean
This method returns the Comm Status.This method returns the commStatusEvent object if Comm Status Monitor is enabled.This method returns the current run mode.This method returns the dashboard object.This method returns the Disabled robot mode object.static FrcRobotBase
This method returns the saved instance.static long
This method returns the loop counter.static long
This method returns the slow loop counter.This method returns the TeleOp robot mode object.This method returns the Test robot mode object.void
printPerformanceMetrics
(TrcDbgTrace tracer) This method prints the performance metrics of all loops and taska.abstract void
This method is called to initialize the robot.abstract void
robotPeriodic
(TrcRobot.RunMode runMode, boolean slowPeriodicLoop) This method is called periodically in the specified run mode.abstract void
robotStartMode
(TrcRobot.RunMode runMode, TrcRobot.RunMode prevMode) This method is called to prepare the robot before a robot mode is about to start.abstract void
robotStopMode
(TrcRobot.RunMode runMode, TrcRobot.RunMode nextMode) This method is called to prepare the robot right after a robot mode has been stopped.void
This method sends a heart beat to the main robot thread watchdog.void
setCommStatusMonitorEnabled
(TrcEvent.Callback callback) This method enables/disables Comm Status monitoring.void
setupRobotModes
(TrcRobot.RobotMode teleOpMode, TrcRobot.RobotMode autoMode, TrcRobot.RobotMode testMode, TrcRobot.RobotMode disabledMode) This method is called by the subclass to set up various robot mode objects.void
Start the competition match.toString()
This method returns the robot name.Methods inherited from class edu.wpi.first.wpilibj.RobotBase
close, getMainThreadId, getRuntimeType, isAutonomous, isAutonomousEnabled, isDisabled, isEnabled, isReal, isSimulation, isTeleop, isTeleopEnabled, isTest, isTestEnabled, startRobot, suppressExitWarning
-
Constructor Details
-
FrcRobotBase
Constructor: Create an instance of the object.- Parameters:
robotName
- specifies the robot name.
-
-
Method Details
-
robotInit
public abstract void robotInit()This method is called to initialize the robot. -
robotStartMode
This method is called to prepare the robot before a robot mode is about to start.- Parameters:
runMode
- specifies the current run mode.prevMode
- specifies the previous run mode.
-
robotStopMode
This method is called to prepare the robot right after a robot mode has been stopped.- Parameters:
runMode
- specifies the current run mode.nextMode
- specifies the next run mode.
-
robotPeriodic
This method is called periodically in the specified run mode. This is typically used to execute periodic tasks that's common to all run modes.- Parameters:
runMode
- specifies the current run mode.slowPeriodicLoop
- specifies true if it is running the slow periodic loop on the main robot thread, false otherwise.
-
getInstance
This method returns the saved instance. This is a static method. So other class can get to this class instance by calling getInstance(). This is very useful for other classes that need to access the public fields and methods.- Returns:
- save instance of this class.
-
toString
This method returns the robot name. -
getDashboard
This method returns the dashboard object.- Returns:
- dashboard object.
-
getLoopCounter
public static long getLoopCounter()This method returns the loop counter. This is very useful for code to determine if it is called multiple times in the same loop. For example, it can be used to optimize sensor access so that if the sensor is accessed in the same loop, there is no reason to create a new bus transaction to get "fresh" data from the sensor.- Returns:
- loop counter value.
-
getSlowLoopCounter
public static long getSlowLoopCounter()This method returns the slow loop counter. This is very useful for code to determine if it is called multiple times in the same slow loop. For example, it can be used to optimize sensor access so that if the sensor is accessed in the same loop, there is no reason to create a new bus transaction to get "fresh" data from the sensor.- Returns:
- slow loop counter value.
-
getCurrentRunMode
This method returns the current run mode.- Returns:
- current run mode.
-
setupRobotModes
public void setupRobotModes(TrcRobot.RobotMode teleOpMode, TrcRobot.RobotMode autoMode, TrcRobot.RobotMode testMode, TrcRobot.RobotMode disabledMode) This method is called by the subclass to set up various robot mode objects.- Parameters:
teleOpMode
- specifies the TeleOp mode object.autoMode
- specifies the Autonomous mode object.testMode
- specifies the Test mode object.disabledMode
- specifies the Disabled mode object.
-
getTeleOpMode
This method returns the TeleOp robot mode object.- Returns:
- TeleOp robot mode object or null if not yet set.
-
getAutoMode
This method returns the Autonomous robot mode object.- Returns:
- Autonomous robot mode object or null if not yet set.
-
getTestMode
This method returns the Test robot mode object.- Returns:
- Test robot mode object or null if not yet set.
-
getDisabledMode
This method returns the Disabled robot mode object.- Returns:
- Disabled robot mode object or null if not yet set.
-
sendWatchdogHeartBeat
public void sendWatchdogHeartBeat()This method sends a heart beat to the main robot thread watchdog. This is important if during robot init time that the user code decided to synchronously busy wait for something, it must periodically call this method to prevent the watchdog from complaining. -
getCommStatus
public boolean getCommStatus()This method returns the Comm Status.- Returns:
- true if comm is still active, false if we lost comm.
-
setCommStatusMonitorEnabled
This method enables/disables Comm Status monitoring. This is very useful for detecting comm lost or comm reconnect.- Parameters:
callback
- specifies the callback handler to enable Comm Status monitoring, null to disable.
-
getCommStatusEvent
This method returns the commStatusEvent object if Comm Status Monitor is enabled.- Returns:
- commStatusEvent object, null if Comm Status Monitor is not enabled.
-
startCompetition
public void startCompetition()Start the competition match. This specific startCompetition() implements "main loop" behavior like that of the FRC TimedRobot, with a primary "fast loop" running at a fast periodic rate (default 50 Hz). In addition, it also runs a "slow loop" running at a slow periodic rate (default to 20 Hz). This code needs to track the order of the modes starting to ensure that everything happens in the right order. Repeatedly run the correct method, either Autonomous or TeleOp when the robot is enabled. After running the correct method, wait for some state to change, either the other mode starts or the robot is disabled. Then go back and wait for the robot to be enabled again.- Specified by:
startCompetition
in classedu.wpi.first.wpilibj.RobotBase
-
endCompetition
public void endCompetition()Called to end the competition loop.- Specified by:
endCompetition
in classedu.wpi.first.wpilibj.RobotBase
-
printPerformanceMetrics
This method prints the performance metrics of all loops and taska.- Parameters:
tracer
- specifies the tracer to be used for printing the performance metrics.
-