The VM is configured to automatically run this class, and to call the functions corresponding to each mode, as described in the TimedRobot documentation. More...
Public Member Functions | |
| void | robotInit () |
| This function is run when the robot is first started up and should be used for any initialization code. | |
| void | robotPeriodic () |
| This function is called every robot packet, no matter the mode. | |
| void | autonomousInit () |
| This autonomous (along with the chooser code above) shows how to select between different autonomous modes using the dashboard. | |
| void | autonomousPeriodic () |
| This function is called periodically during autonomous. | |
| void | teleopInit () |
| This function is called once when teleop is enabled. | |
| void | teleopPeriodic () |
| This function is called periodically during operator control. | |
| void | disabledInit () |
| This function is called once when the robot is disabled. | |
| void | disabledPeriodic () |
| This function is called periodically when disabled. | |
| void | testInit () |
| This function is called once when test mode is enabled. | |
| void | testPeriodic () |
| This function is called periodically during test mode. | |
Private Member Functions | |
| void | checkForModeSwitches () |
| Switches between different driving modes For the DPad, 0 is up, and angles go clockwise, so 90 is right. | |
| void | checkForButtonPresses () |
| Checks for button presses and activates their functions. | |
| void | autonomousCheckForButtonPresses () |
| void | drive () |
| Powers motors based on the analog inputs. | |
Private Attributes | |
| String | m_autoSelected |
| final SendableChooser< String > | m_chooser = new SendableChooser<>() |
| Controller | xboxController = new Controller() |
| MecaDrive | driveBase = new MecaDrive(Constants.FL_TALON_ID, Constants.FR_TALON_ID, Constants.RL_TALON_ID, Constants.RR_TALON_ID, imu) |
Static Private Attributes | |
| static final String | kDefaultAuto = "Default" |
| static final String | kCustomAuto = "My Auto" |
The VM is configured to automatically run this class, and to call the functions corresponding to each mode, as described in the TimedRobot documentation.
If you change the name of this class or the package after creating this project, you must also update the build.gradle file in the project.
Definition at line 25 of file Robot.java.
|
private |
Definition at line 206 of file Robot.java.
References frc.robot.Robot.driveBase, frc.robot.subsystems.MecaDrive.getPose(), frc.robot.subsystems.DriveBase.resetCurrentTrajectoryTime(), frc.robot.subsystems.Autonomous.updateTrajectory(), and frc.robot.Robot.xboxController.
Referenced by frc.robot.Robot.autonomousPeriodic().
| void frc.robot.Robot.autonomousInit | ( | ) |
This autonomous (along with the chooser code above) shows how to select between different autonomous modes using the dashboard.
The sendable chooser code works with the Java SmartDashboard. If you prefer the LabVIEW Dashboard, remove all of the chooser code and uncomment the getString line to get the auto name from the text box below the Gyro
You can add additional auto modes by adding additional comparisons to the switch structure below with additional strings. If using the SendableChooser make sure to add them to the chooser code above as well.
Definition at line 100 of file Robot.java.
References frc.robot.Robot.driveBase, frc.robot.Robot.m_autoSelected, frc.robot.Robot.m_chooser, and frc.robot.subsystems.DriveBase.resetCurrentTrajectoryTime().
| void frc.robot.Robot.autonomousPeriodic | ( | ) |
This function is called periodically during autonomous.
Definition at line 110 of file Robot.java.
References frc.robot.subsystems.Autonomous.applyChassisSpeeds(), frc.robot.Robot.autonomousCheckForButtonPresses(), frc.robot.subsystems.MecaDrive.drive(), frc.robot.Robot.driveBase, and frc.robot.subsystems.DriveBase.incrementCurrentTrajectoryTime().
|
private |
Checks for button presses and activates their functions.
Definition at line 191 of file Robot.java.
References frc.robot.subsystems.MecaDrive.cycleMotor(), frc.robot.subsystems.DriveBase.decreaseSpeedBracket(), frc.robot.Robot.driveBase, frc.robot.subsystems.DriveBase.increaseSpeedBracket(), frc.robot.subsystems.MecaDrive.printActiveMotorDebugMode(), and frc.robot.Robot.xboxController.
Referenced by frc.robot.Robot.teleopPeriodic().
|
private |
Switches between different driving modes For the DPad, 0 is up, and angles go clockwise, so 90 is right.
Definition at line 177 of file Robot.java.
References frc.robot.Robot.driveBase, frc.robot.subsystems.DriveBase.turnOnDebugMode(), frc.robot.subsystems.DriveBase.turnOnDefaultMode(), frc.robot.subsystems.DriveBase.turnONPIDTuningMode(), frc.robot.subsystems.DriveBase.turnOnStopMode(), and frc.robot.Robot.xboxController.
Referenced by frc.robot.Robot.teleopPeriodic().
| void frc.robot.Robot.disabledInit | ( | ) |
This function is called once when the robot is disabled.
Definition at line 159 of file Robot.java.
| void frc.robot.Robot.disabledPeriodic | ( | ) |
This function is called periodically when disabled.
Definition at line 163 of file Robot.java.
|
private |
Powers motors based on the analog inputs.
Definition at line 224 of file Robot.java.
References frc.robot.subsystems.MecaDrive.drive(), frc.robot.Robot.driveBase, frc.robot.subsystems.Controller.getLeftX(), frc.robot.subsystems.Controller.getLeftY(), frc.robot.subsystems.Controller.getRightX(), and frc.robot.Robot.xboxController.
Referenced by frc.robot.Robot.teleopPeriodic().
| void frc.robot.Robot.robotInit | ( | ) |
This function is run when the robot is first started up and should be used for any initialization code.
Definition at line 51 of file Robot.java.
References frc.robot.Robot.kCustomAuto, frc.robot.Robot.kDefaultAuto, and frc.robot.Robot.m_chooser.
| void frc.robot.Robot.robotPeriodic | ( | ) |
This function is called every robot packet, no matter the mode.
Use this for items like diagnostics that you want ran during disabled, autonomous, teleoperated and test.
This runs after the mode specific periodic functions, but before LiveWindow and SmartDashboard integrated updating.
Definition at line 73 of file Robot.java.
References frc.robot.Robot.driveBase, frc.robot.subsystems.BetterShuffleboard.pushDashboard(), and frc.robot.subsystems.MecaDrive.updateOdometry().
| void frc.robot.Robot.teleopInit | ( | ) |
This function is called once when teleop is enabled.
Definition at line 139 of file Robot.java.
References frc.robot.subsystems.BetterShuffleboard.updateControllerExponents().
| void frc.robot.Robot.teleopPeriodic | ( | ) |
This function is called periodically during operator control.
Definition at line 145 of file Robot.java.
References frc.robot.Robot.checkForButtonPresses(), frc.robot.Robot.checkForModeSwitches(), and frc.robot.Robot.drive().
| void frc.robot.Robot.testInit | ( | ) |
This function is called once when test mode is enabled.
Definition at line 167 of file Robot.java.
| void frc.robot.Robot.testPeriodic | ( | ) |
This function is called periodically during test mode.
Definition at line 171 of file Robot.java.
|
private |
Definition at line 39 of file Robot.java.
Referenced by frc.robot.Robot.autonomousCheckForButtonPresses(), frc.robot.Robot.autonomousInit(), frc.robot.Robot.autonomousPeriodic(), frc.robot.Robot.checkForButtonPresses(), frc.robot.Robot.checkForModeSwitches(), frc.robot.Robot.drive(), and frc.robot.Robot.robotPeriodic().
|
staticprivate |
Definition at line 29 of file Robot.java.
Referenced by frc.robot.Robot.robotInit().
|
staticprivate |
Definition at line 28 of file Robot.java.
Referenced by frc.robot.Robot.robotInit().
|
private |
Definition at line 30 of file Robot.java.
Referenced by frc.robot.Robot.autonomousInit().
|
private |
Definition at line 31 of file Robot.java.
Referenced by frc.robot.Robot.autonomousInit(), and frc.robot.Robot.robotInit().
|
private |
Definition at line 38 of file Robot.java.
Referenced by frc.robot.Robot.autonomousCheckForButtonPresses(), frc.robot.Robot.checkForButtonPresses(), frc.robot.Robot.checkForModeSwitches(), and frc.robot.Robot.drive().