2023 Drive base
 
Loading...
Searching...
No Matches
frc.robot.Robot Class Reference

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...

Inheritance diagram for frc.robot.Robot:

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"
 

Detailed Description

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.

Member Function Documentation

◆ autonomousCheckForButtonPresses()

void frc.robot.Robot.autonomousCheckForButtonPresses ( )
private

Definition at line 206 of file Robot.java.

206 {
207 if (xboxController.getBButtonPressed()) {
208 // create an example trajectory
209 Pose2d current = driveBase.getPose();
210
211 // start with a small displacement ( + 1)
212 Pose2d target = new Pose2d(current.getX() + 1, current.getY(), current.getRotation());
215 }
216 if (xboxController.getAButtonPressed()){
217 // toggle autonomous is moving
218 autonomousIsMoving = !autonomousIsMoving;
219 }
220 }
Controller xboxController
Definition: Robot.java:38
MecaDrive driveBase
Definition: Robot.java:39
Contains functions for moving in autonomous mode, such as setting the robots trajectory,...
Definition: Autonomous.java:18
static void updateTrajectory(MecaDrive m_drive, Pose2d target, ArrayList< Translation2d > interiorWaypoints)
Generate a 2d cartesian trajectory (line/spline) and apply it to robot, with the endpoint given,...
Definition: Autonomous.java:32
Pose2d getPose()
Returns the currently-estimated pose of the robot.
Definition: MecaDrive.java:258

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().

◆ autonomousInit()

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.

100 {
101 m_autoSelected = m_chooser.getSelected();
102 // m_autoSelected = SmartDashboard.getString("Auto Selector", kDefaultAuto);
103 System.out.println("Auto selected: " + m_autoSelected);
104
106 }
String m_autoSelected
Definition: Robot.java:30
final SendableChooser< String > m_chooser
Definition: Robot.java:31

References frc.robot.Robot.driveBase, frc.robot.Robot.m_autoSelected, frc.robot.Robot.m_chooser, and frc.robot.subsystems.DriveBase.resetCurrentTrajectoryTime().

◆ autonomousPeriodic()

void frc.robot.Robot.autonomousPeriodic ( )

This function is called periodically during autonomous.

Definition at line 110 of file Robot.java.

110 {
111 // switch (m_autoSelected) {
112 // case kCustomAuto:
113 // // Put custom auto code here
114 // break;
115 // case kDefaultAuto:
116 // default:
117 // break;
118 // // Default code
119 // }
120
122
123
124 if (autonomousIsMoving){
125 // increase the current time, because autonomous trajectories need a time (each period takes the same time)
127 System.out.println("Moving");
128 // tell the autonomous system to use it's trajectory from the drivebase to drive the robot
130 }
131 else {
132 driveBase.drive(0, 0, 0);
133 }
134
135 }
void autonomousCheckForButtonPresses()
Definition: Robot.java:206
static void applyChassisSpeeds(MecaDrive m_drive)
using the chassis speeds from the trajectory specified by the robot, drive the robot
Definition: Autonomous.java:63
void drive(double speedX, double speedY, double rotateSpeed)
Definition: MecaDrive.java:76

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().

◆ checkForButtonPresses()

void frc.robot.Robot.checkForButtonPresses ( )
private

Checks for button presses and activates their functions.

Definition at line 191 of file Robot.java.

191 {
192 if (xboxController.getAButtonPressed()) {
194 }
195 if (xboxController.getBButtonPressed()) {
197 }
198 if (xboxController.getLeftBumperPressed()) {
200 }
201 if (xboxController.getRightBumperPressed()) {
203 }
204 }
void increaseSpeedBracket()
The speed bracket controls the multiplier for al the speeds So when you change it,...
Definition: DriveBase.java:67
void cycleMotor()
Cycle between each motor during debug mode.
Definition: MecaDrive.java:170
void printActiveMotorDebugMode()
prints the number of the currently activated motors during debug mode
Definition: MecaDrive.java:181

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().

◆ checkForModeSwitches()

void frc.robot.Robot.checkForModeSwitches ( )
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.

177 {
178 // up
179 if (xboxController.getPOV() == 0) driveBase.turnOnDefaultMode();
180 // right
181 if (xboxController.getPOV() == 90) driveBase.turnOnStopMode();
182 // left
183 if (xboxController.getPOV() == 270) driveBase.turnOnDebugMode();
184 // down
185 if (xboxController.getPOV() == 180) driveBase.turnONPIDTuningMode();
186 }
void turnOnStopMode()
should be overridden for actual functionality because depends on drive base specifc speeds (for tank ...
Definition: DriveBase.java:101

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().

◆ disabledInit()

void frc.robot.Robot.disabledInit ( )

This function is called once when the robot is disabled.

Definition at line 159 of file Robot.java.

159{}

◆ disabledPeriodic()

void frc.robot.Robot.disabledPeriodic ( )

This function is called periodically when disabled.

Definition at line 163 of file Robot.java.

163{}

◆ drive()

void frc.robot.Robot.drive ( )
private

Powers motors based on the analog inputs.

Definition at line 224 of file Robot.java.

224 {
225 // process input (determine wheelspeeds)
226 // driveBase.drive(xboxController.getLeftX(), xboxController.getLeftY(), xboxController.getRightX(), xboxController.getRightY());
228 }

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().

◆ robotInit()

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.

51 {
52 m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
53 m_chooser.addOption("My Auto", kCustomAuto);
54 SmartDashboard.putData("Auto choices", m_chooser);
55 // CameraServer.startAutomaticCapture(0);
56 // CameraServer.startAutomaticCapture(1);
57
58 //limelight.printVal();
59 //limelight.smartDash();
60
61 // tank drive initialization
62 // driveBase = createTankDrive();
63 }
static final String kCustomAuto
Definition: Robot.java:29
static final String kDefaultAuto
Definition: Robot.java:28

References frc.robot.Robot.kCustomAuto, frc.robot.Robot.kDefaultAuto, and frc.robot.Robot.m_chooser.

◆ robotPeriodic()

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.

73 {
74
76
77 // SmartDashboard.putNumber("test", test);
78 // limelight.test();
79 // System.out.println("hello wo5rld");
80
81 // test += 1;
82
83 if (counter % 10 == 0) {
84 smartdash.pushDashboard(limelight, imu, driveBase, zed);
85 }
86 counter++;
87 }
void pushDashboard(Limelight limelight, IMU imu, MecaDrive drive, ZED zed)

References frc.robot.Robot.driveBase, frc.robot.subsystems.BetterShuffleboard.pushDashboard(), and frc.robot.subsystems.MecaDrive.updateOdometry().

◆ teleopInit()

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().

◆ teleopPeriodic()

void frc.robot.Robot.teleopPeriodic ( )

This function is called periodically during operator control.

Definition at line 145 of file Robot.java.

145 {
146
147 // switch between driving modes
149
150 // check for button/bumper presses
152
153 // powers motors based on the analog inputs
154 drive();
155 }
void checkForModeSwitches()
Switches between different driving modes For the DPad, 0 is up, and angles go clockwise,...
Definition: Robot.java:177
void checkForButtonPresses()
Checks for button presses and activates their functions.
Definition: Robot.java:191
void drive()
Powers motors based on the analog inputs.
Definition: Robot.java:224

References frc.robot.Robot.checkForButtonPresses(), frc.robot.Robot.checkForModeSwitches(), and frc.robot.Robot.drive().

◆ testInit()

void frc.robot.Robot.testInit ( )

This function is called once when test mode is enabled.

Definition at line 167 of file Robot.java.

167{}

◆ testPeriodic()

void frc.robot.Robot.testPeriodic ( )

This function is called periodically during test mode.

Definition at line 171 of file Robot.java.

171{}

Member Data Documentation

◆ driveBase

◆ kCustomAuto

final String frc.robot.Robot.kCustomAuto = "My Auto"
staticprivate

Definition at line 29 of file Robot.java.

Referenced by frc.robot.Robot.robotInit().

◆ kDefaultAuto

final String frc.robot.Robot.kDefaultAuto = "Default"
staticprivate

Definition at line 28 of file Robot.java.

Referenced by frc.robot.Robot.robotInit().

◆ m_autoSelected

String frc.robot.Robot.m_autoSelected
private

Definition at line 30 of file Robot.java.

Referenced by frc.robot.Robot.autonomousInit().

◆ m_chooser

final SendableChooser<String> frc.robot.Robot.m_chooser = new SendableChooser<>()
private

Definition at line 31 of file Robot.java.

Referenced by frc.robot.Robot.autonomousInit(), and frc.robot.Robot.robotInit().

◆ xboxController


The documentation for this class was generated from the following file: