Creating your Benchtop Test Program (C++/Java)
Once everything is installed, we’re ready to create a robot program. WPILib comes with several templates for robot programs. Use of these templates is highly recommended for new users; however, advanced users are free to write their own robot code from scratch. This article walks through creating a project from one of the provided examples which has some code already written to drive a basic robot.
Creating a New WPILib Project
Bring up the Visual Studio Code command palette with Ctrl+Shift+P. Then, type “WPILib” into the prompt. Since all WPILib commands start with “WPILib”, this will bring up the list of WPILib-specific VS Code commands. Now, select the “Create a new project” command:
This will bring up the “New Project Creator Window:”
The elements of the New Project Creator Window are explained below:
Project Type: The kind of project we wish to create. For this example, select Example
Language: This is the language (C++ or Java) that will be used for this project.
Project Base: This box is used to select the base class or example to generate the project from. For this example, select Getting Started
Base Folder: This determines the folder in which the robot project will be located.
Project Name: The name of the robot project. This also specifies the name that the project folder will be given if the Create New Folder box is checked.
Create a New Folder: If this is checked, a new folder will be created to hold the project within the previously-specified folder. If it is not checked, the project will be located directly in the previously-specified folder. An error will be thrown if the folder is not empty and this is not checked. project folder will be given if the Create New Folder box is checked.
Team Number: The team number for the project, which will be used for package names within the project and to locate the robot when deploying code.
Enable Desktop Support: Enables unit test and simulation. While WPILib supports this, third party software libraries may not. If libraries do not support desktop, then your code may not compile or may crash. It should be left unchecked unless unit testing or simulation is needed and all libraries support it. For this example, do not check this box.
Once all the above have been configured, click “Generate Project” and the robot project will be created.
Note
Any errors in project generation will appear in the bottom right-hand corner of the screen.
Opening The New Project
After successfully creating your project, VS Code will give the option of opening the project as shown above. We can choose to do that now or later by typing Ctrl+K then Ctrl+O (or just Command+O on macOS) and select the folder where we saved our project.
Click Yes I trust the authors.
Once opened we will see the project hierarchy on the left. Double clicking on the file will open that file in the editor.
C++ Configurations (C++ Only)
For C++ projects, there is one more step to set up IntelliSense. Whenever we open a project, we should get a pop-up in the bottom right corner asking to refresh C++ configurations. Click “Yes” to set up IntelliSense.
Imports/Includes
7import edu.wpi.first.wpilibj.Joystick;
8import edu.wpi.first.wpilibj.TimedRobot;
9import edu.wpi.first.wpilibj.Timer;
10import edu.wpi.first.wpilibj.drive.DifferentialDrive;
11import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
5#include <frc/Joystick.h>
6#include <frc/TimedRobot.h>
7#include <frc/Timer.h>
8#include <frc/drive/DifferentialDrive.h>
9#include <frc/motorcontrol/PWMSparkMax.h>
Our code needs to reference the components of WPILib that are used. In C++ this is accomplished using #include
statements; in Java it is done with import
statements. The program references classes for Joystick
(for driving), PWMSparkMax
(for controlling motors), TimedRobot
(the base class used for the example), Timer
(used for autonomous), DifferentialDrive
(for connecting the joystick control to the motors), and LiveWindow
(C++ only).
Defining the variables for our sample robot
19public class Robot extends TimedRobot {
20 private final PWMSparkMax m_leftDrive = new PWMSparkMax(0);
21 private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
22 private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive, m_rightDrive);
23 private final Joystick m_stick = new Joystick(0);
24 private final Timer m_timer = new Timer();
12 public:
13 Robot() {
14 m_right.SetInverted(true);
15 m_robotDrive.SetExpiration(100_ms);
16 // We need to invert one side of the drivetrain so that positive voltages
17 // result in both sides moving forward. Depending on how your robot's
18 // gearbox is constructed, you might have to invert the left side instead.
19 m_timer.Start();
20 }
49 private:
50 // Robot drive system
51 frc::PWMSparkMax m_left{0};
52 frc::PWMSparkMax m_right{1};
53 frc::DifferentialDrive m_robotDrive{m_left, m_right};
54
55 frc::Joystick m_stick{0};
56 frc::Timer m_timer;
57};
The sample robot in our examples will have a joystick on USB port 0 for arcade drive and two motors on PWM ports 0 and 1. Here we create objects of type DifferentialDrive (m_robotDrive), Joystick (m_stick) and Timer (m_timer). This section of the code does three things:
Defines the variables as members of our Robot class.
Initializes the variables.
Note
The variable initializations for C++ are in the private
section at the bottom of the program. This means they are private to the class (Robot
). The C++ code also sets the Motor Safety expiration to 0.1 seconds (the drive will shut off if we don’t give it a command every .1 seconds) and starts the Timer
used for autonomous.
Robot Initialization
@Override
public void robotInit() {}
void RobotInit() {}
The RobotInit
method is run when the robot program is starting up, but after the constructor. The RobotInit
for our sample program doesn’t do anything. If we wanted to run something here we could provide the code above to override the default).
Simple Autonomous Example
38 /** This function is run once each time the robot enters autonomous mode. */
39 @Override
40 public void autonomousInit() {
41 m_timer.reset();
42 m_timer.start();
43 }
44
45 /** This function is called periodically during autonomous. */
46 @Override
47 public void autonomousPeriodic() {
48 // Drive for 2 seconds
49 if (m_timer.get() < 2.0) {
50 m_robotDrive.arcadeDrive(0.5, 0.0); // drive forwards half speed
51 } else {
52 m_robotDrive.stopMotor(); // stop robot
53 }
54 }
22 void AutonomousInit() override {
23 m_timer.Reset();
24 m_timer.Start();
25 }
26
27 void AutonomousPeriodic() override {
28 // Drive for 2 seconds
29 if (m_timer.Get() < 2_s) {
30 // Drive forwards half speed
31 m_robotDrive.ArcadeDrive(0.5, 0.0);
32 } else {
33 // Stop robot
34 m_robotDrive.ArcadeDrive(0.0, 0.0);
35 }
36 }
The AutonomousInit
method is run once each time the robot transitions to autonomous from another mode. In this program, we reset the Timer
and then start it in this method.
AutonomousPeriodic
is run once every period while the robot is in autonomous mode. In the TimedRobot
class the period is a fixed time, which defaults to 20ms. In this example, the periodic code checks if the timer is less than 2 seconds and if so, drives forward at half speed using the ArcadeDrive
method of the DifferentialDrive
class. If more than 2 seconds has elapsed, the code stops the robot drive.
Joystick Control for teleoperation
56 /** This function is called once each time the robot enters teleoperated mode. */
57 @Override
58 public void teleopInit() {}
59
60 /** This function is called periodically during teleoperated mode. */
61 @Override
62 public void teleopPeriodic() {
63 m_robotDrive.arcadeDrive(m_stick.getY(), m_stick.getX());
64 }
38 void TeleopInit() override {}
39
40 void TeleopPeriodic() override {
41 // Drive with arcade style (use right stick)
42 m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
43 }
Like in Autonomous, the Teleop mode has a TeleopInit
and TeleopPeriodic
function. In this example we don’t have anything to do in TeleopInit
, it is provided for illustration purposes only. In TeleopPeriodic
, the code uses the ArcadeDrive
method to map the Y-axis of the Joystick
to forward/back motion of the drive motors and the X-axis to turning motion.
Test Mode
66 /** This function is called once each time the robot enters test mode. */
67 @Override
68 public void testInit() {}
69
70 /** This function is called periodically during test mode. */
71 @Override
72 public void testPeriodic() {}
73}
45 void TestInit() override {}
46
47 void TestPeriodic() override {}
Test Mode is used for testing robot functionality. Similar to TeleopInit
, the TestInit
and TestPeriodic
methods are provided here for illustrative purposes only.