Creating your Test Drivetrain Program (Java/C++/Python)

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.

Important

This guide includes code examples that involve vendor hardware for the convenience of the user. In this document, PWM refers to the motor controller included in the KOP. The CTRE tab references the Talon FX motor controller (Falcon 500 motor), but usage is similar for TalonSRX and VictorSPX. The REV tab references the CAN SPARK MAX controlling a brushless motor, but it’s similar for brushed motor. There is an assumption that the user has already installed the required vendordeps and configured the device(s) (update firmware, assign CAN IDs, etc) according to the manufacturer documentation (CTRE / REV).

Creating a New WPILib Project (Java/C++)

In Visual Studio Code, click the WPILib logo in the top right to launch the WPILib Command Palette. Select Create a new project:

Choose "WPILib: Create a new project".

This will bring up the “WPILIb New Project Creator”

The project type selector of the WPILib New Project Creator

The Project Type chooses between an empty template project, or a WPILib example project. For this example, select Example and then choose Next.

This will bring up the language and base selection window.

The language and base page of the WPILib New Project Creator
  1. Language: This is the language (C++ or Java) that will be used for this project.

  2. Project Base: This box is used to select the base class or example to generate the project from. For this example, select Getting Started

After making the selections, click Next.

This will bring up the Project and Configuration window.

The project and configuration page of the WPILib New Project Creator
  1. Base Folder: This determines the folder in which the robot project will be located.

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

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

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

  5. Enable Desktop Support: Enables unit test and simulation support (see Introduction to Robot 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.

Warning

Creating projects on OneDrive is not supported as OneDrive’s caching interferes with the build system. Some Windows installations put the Documents and Desktop folders on OneDrive by default.

Once all the above have been configured, click Next.

This will bring up the Review and Create window.

The review and create page of the WPILib New Project Creator

Double check all the settings and click Create Project. If anything is not correct, click Back and make the necessary corrections.

Note

Any errors in project generation will appear in the bottom right-hand corner of the screen.

Opening The New Project

Open Project Dialog in VS Code

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.

Trusted Workspace dialog in VS Code.

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.

The robot.java code shown after opening a new project.

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.

You must choose "Yes" to refresh the C++ configurations.

Creating a New WPILib Project (Python)

Running the robotpy init command will initialize a new robot project:

py -3 -m robotpy init
python3 -m robotpy init
python3 -m robotpy init

This will create a robot.py and pyproject.toml file, but will not overwrite an existing file.

  • The pyproject.toml file contains the requirements for your project, which are downloaded and installed via the robotpy sync command.

  • The robot.py file is where you will put the your Robot class.

Basic Drivetrain example

First, here is what a simple code can look like for a Drivetrain with PWM controlled motors (such as SparkMax).

 1// Copyright (c) FIRST and other WPILib contributors.
 2// Open Source Software; you can modify and/or share it under the terms of
 3// the WPILib BSD license file in the root directory of this project.
 4
 5package org.wpilib.examples.gettingstarted;
 6
 7import org.wpilib.drive.DifferentialDrive;
 8import org.wpilib.driverstation.Gamepad;
 9import org.wpilib.framework.TimedRobot;
10import org.wpilib.hardware.motor.PWMSparkMax;
11import org.wpilib.system.Timer;
12import org.wpilib.util.sendable.SendableRegistry;
13
14/**
15 * The methods in this class are called automatically corresponding to each mode, as described in
16 * the TimedRobot documentation. If you change the name of this class or the package after creating
17 * this project, you must also update the manifest file in the resource directory.
18 */
19public class Robot extends TimedRobot {
20  private final PWMSparkMax leftDrive = new PWMSparkMax(0);
21  private final PWMSparkMax rightDrive = new PWMSparkMax(1);
22  private final DifferentialDrive robotDrive =
23      new DifferentialDrive(leftDrive::setThrottle, rightDrive::setThrottle);
24  private final Gamepad controller = new Gamepad(0);
25  private final Timer timer = new Timer();
26
27  /** Called once at the beginning of the robot program. */
28  public Robot() {
29    SendableRegistry.addChild(robotDrive, leftDrive);
30    SendableRegistry.addChild(robotDrive, rightDrive);
31
32    // We need to invert one side of the drivetrain so that positive voltages
33    // result in both sides moving forward. Depending on how your robot's
34    // gearbox is constructed, you might have to invert the left side instead.
35    rightDrive.setInverted(true);
36  }
37
38  /** This function is run once each time the robot enters autonomous mode. */
39  @Override
40  public void autonomousInit() {
41    timer.restart();
42  }
43
44  /** This function is called periodically during autonomous. */
45  @Override
46  public void autonomousPeriodic() {
47    // Drive for 2 seconds
48    if (timer.get() < 2.0) {
49      // Drive forwards half velocity, make sure to turn input squaring off
50      robotDrive.arcadeDrive(0.5, 0.0, false);
51    } else {
52      robotDrive.stopMotor(); // stop robot
53    }
54  }
55
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    robotDrive.arcadeDrive(-controller.getLeftY(), -controller.getRightX());
64  }
65
66  /** This function is called once each time the robot enters utility mode. */
67  @Override
68  public void utilityInit() {}
69
70  /** This function is called periodically during utility mode. */
71  @Override
72  public void utilityPeriodic() {}
73}
 1// Copyright (c) FIRST and other WPILib contributors.
 2// Open Source Software; you can modify and/or share it under the terms of
 3// the WPILib BSD license file in the root directory of this project.
 4
 5#include "wpi/drive/DifferentialDrive.hpp"
 6#include "wpi/driverstation/Gamepad.hpp"
 7#include "wpi/framework/TimedRobot.hpp"
 8#include "wpi/hardware/motor/PWMSparkMax.hpp"
 9#include "wpi/system/Timer.hpp"
10
11class Robot : public wpi::TimedRobot {
12 public:
13  Robot() {
14    wpi::util::SendableRegistry::AddChild(&robotDrive, &left);
15    wpi::util::SendableRegistry::AddChild(&robotDrive, &right);
16
17    // We need to invert one side of the drivetrain so that positive voltages
18    // result in both sides moving forward. Depending on how your robot's
19    // gearbox is constructed, you might have to invert the left side instead.
20    right.SetInverted(true);
21    robotDrive.SetExpiration(100_ms);
22    timer.Start();
23  }
24
25  void AutonomousInit() override { timer.Restart(); }
26
27  void AutonomousPeriodic() override {
28    // Drive for 2 seconds
29    if (timer.Get() < 2_s) {
30      // Drive forwards half velocity, make sure to turn input squaring off
31      robotDrive.ArcadeDrive(0.5, 0.0, false);
32    } else {
33      // Stop robot
34      robotDrive.ArcadeDrive(0.0, 0.0, false);
35    }
36  }
37
38  void TeleopInit() override {}
39
40  void TeleopPeriodic() override {
41    // Drive with arcade style (use right stick to steer)
42    robotDrive.ArcadeDrive(-controller.GetLeftY(), controller.GetRightX());
43  }
44
45  void UtilityInit() override {}
46
47  void UtilityPeriodic() override {}
48
49 private:
50  // Robot drive system
51  wpi::PWMSparkMax left{0};
52  wpi::PWMSparkMax right{1};
53  wpi::DifferentialDrive robotDrive{
54      [&](double output) { left.SetThrottle(output); },
55      [&](double output) { right.SetThrottle(output); }};
56
57  wpi::Gamepad controller{0};
58  wpi::Timer timer;
59};
60
61#ifndef RUNNING_WPILIB_TESTS
62int main() {
63  return wpi::StartRobot<Robot>();
64}
65#endif
 1#!/usr/bin/env python3
 2#
 3# Copyright (c) FIRST and other WPILib contributors.
 4# Open Source Software; you can modify and/or share it under the terms of
 5# the WPILib BSD license file in the root directory of this project.
 6#
 7
 8import wpilib
 9
10
11class MyRobot(wpilib.TimedRobot):
12    def __init__(self):
13        """
14        This function is called upon program startup and
15        should be used for any initialization code.
16        """
17        super().__init__()
18        self.leftDrive = wpilib.PWMSparkMax(0)
19        self.rightDrive = wpilib.PWMSparkMax(1)
20        self.robotDrive = wpilib.DifferentialDrive(self.leftDrive, self.rightDrive)
21        self.controller = wpilib.NiDsXboxController(0)
22        self.timer = wpilib.Timer()
23
24        # We need to invert one side of the drivetrain so that positive voltages
25        # result in both sides moving forward. Depending on how your robot's
26        # gearbox is constructed, you might have to invert the left side instead.
27        self.rightDrive.setInverted(True)
28
29    def autonomousInit(self):
30        """This function is run once each time the robot enters autonomous mode."""
31        self.timer.restart()
32
33    def autonomousPeriodic(self):
34        """This function is called periodically during autonomous."""
35
36        # Drive for two seconds
37        if self.timer.get() < 2.0:
38            # Drive forwards half velocity, make sure to turn input squaring off
39            self.robotDrive.arcadeDrive(0.5, 0, squareInputs=False)
40        else:
41            self.robotDrive.stopMotor()  # Stop robot
42
43    def teleopInit(self):
44        """This function is called once each time the robot enters teleoperated mode."""
45
46    def teleopPeriodic(self):
47        """This function is called periodically during teleoperated mode."""
48        self.robotDrive.arcadeDrive(
49            -self.controller.getLeftY(), -self.controller.getRightX()
50        )
51
52    def utilityInit(self):
53        """This function is called once each time the robot enters utility mode."""
54
55    def utilityPeriodic(self):
56        """This function is called periodically during utility mode."""

Now let’s look at various parts of the code.

Imports/Includes

1import org.wpilib.drive.DifferentialDrive;
2import org.wpilib.driverstation.Gamepad;
3import org.wpilib.framework.TimedRobot;
4import org.wpilib.hardware.motor.PWMSparkMax;
5import org.wpilib.system.Timer;
6import org.wpilib.util.sendable.SendableRegistry;
5#include "wpi/drive/DifferentialDrive.hpp"
6#include "wpi/driverstation/Gamepad.hpp"
7#include "wpi/framework/TimedRobot.hpp"
8#include "wpi/hardware/motor/PWMSparkMax.hpp"
9#include "wpi/system/Timer.hpp"
8import wpilib
import org.wpilib.framework.TimedRobot;
import org.wpilib.system.Timer;
import org.wpilib.driverstation.Gamepad;
import org.wpilib.drive.DifferentialDrive;
import com.ctre.phoenix6.hardware.TalonFX;
#include "wpi/framework/TimedRobot.hpp"
#include "wpi/system/Timer.hpp"
#include "wpi/driverstation/Gamepad.hpp"
#include "wpi/drive/DifferentialDrive.hpp"
#include "ctre/phoenix6/TalonFX.hpp"
import wpilib               # Used to get the joysticks
import wpilib.drive         # Used for the DifferentialDrive class
import phoenix6             # CTRE library
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;
import org.wpilib.framework.TimedRobot;
import org.wpilib.system.Timer;
import org.wpilib.driverstation.Gamepad;
import org.wpilib.drive.DifferentialDrive;
#include "wpi/framework/TimedRobot.hpp"
#include "wpi/system/Timer.hpp"
#include "wpi/driverstation/Gamepad.hpp"
#include "wpi/drive/DifferentialDrive.hpp"
#include "wpi/hardware/motor/PWMSparkMax.hpp"
#include "rev/CANSparkMax.h"
import wpilib           # Used to get the joysticks
import wpilib.drive     # Used for the DifferentialDrive class
import rev              # REV library
import org.wpilib.framework.TimedRobot;
import org.wpilib.system.Timer;
import org.wpilib.driverstation.Gamepad;
import org.wpilib.drive.DifferentialDrive;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
#include "wpi/framework/TimedRobot.hpp"
#include "wpi/system/Timer.hpp"
#include "wpi/driverstation/Gamepad.hpp"
#include "wpi/drive/DifferentialDrive.hpp"
#include "ctre/phoenix/motorcontrol/can/WPI_TalonSRX.h"
import wpilib           # Used to get the joysticks
import wpilib.drive     # Used for the DifferentialDrive class
import ctre             # CTRE library

Our code needs to reference the components of WPILib that are used. In C++ this is accomplished using #include statements; in Java and Python it is done with import statements. The program references classes for Gamepad (for driving), PWMSparkMax / TalonFX / CANSparkMax / WPI_TalonSRX (for controlling motors), TimedRobot (the base class used for the example), Timer (used for autonomous), and DifferentialDrive (for connecting the Gamepad to the motors).

Note

The Gamepad class is used with the 2027 FIRST Driver station. If you are using the NI Driver station, you will need to use the NiDsXboxController class instead.

Defining the variables for our sample robot

19public class Robot extends TimedRobot {
20  private final PWMSparkMax leftDrive = new PWMSparkMax(0);
21  private final PWMSparkMax rightDrive = new PWMSparkMax(1);
22  private final DifferentialDrive robotDrive =
23      new DifferentialDrive(leftDrive::setThrottle, rightDrive::setThrottle);
24  private final Gamepad controller = new Gamepad(0);
25  private final Timer timer = new Timer();
50  // Robot drive system
51  wpi::PWMSparkMax left{0};
52  wpi::PWMSparkMax right{1};
53  wpi::DifferentialDrive robotDrive{
54      [&](double output) { left.SetThrottle(output); },
55      [&](double output) { right.SetThrottle(output); }};
56
57  wpi::Gamepad controller{0};
58  wpi::Timer timer;
59};
12class MyRobot(wpilib.TimedRobot):
13    def robotInit(self):
14        """
15        This function is called upon program startup and
16        should be used for any initialization code.
17        """
18        self.leftDrive = wpilib.PWMSparkMax(0)
19        self.rightDrive = wpilib.PWMSparkMax(1)
20        self.robotDrive = wpilib.drive.DifferentialDrive(
21            self.leftDrive, self.rightDrive
22        )
23        self.controller = wpilib.XboxController(0)
24        self.timer = wpilib.Timer()
25
26        # We need to invert one side of the drivetrain so that positive voltages
27        # result in both sides moving forward. Depending on how your robot's
28        # gearbox is constructed, you might have to invert the left side instead.
29        self.rightDrive.setInverted(True)
public class Robot extends TimedRobot {
   private final TalonFX leftDrive = new TalonFX(1);
   private final TalonFX rightDrive = new TalonFX(2);
   private final DifferentialDrive robotDrive =
     new DifferentialDrive(leftDrive::set, rightDrive::set);
   private final Gamepad controller = new Gamepad(0);
   private final Timer timer = new Timer();
private:
 // Robot drive system
 ctre::phoenix6::hardware::TalonFX left{1};
 ctre::phoenix6::hardware::TalonFX right{2};
 wpi::DifferentialDrive robotDrive{
   [&](double output) { left.Set(output); },
   [&](double output) { right.Set(output); }};
 wpi::Gamepad controller{0};
 wpi::Timer timer;
class MyRobot(wpilib.TimedRobot):
  def robotInit(self):
     """
     This function is called upon program startup and
     should be used for any initialization code.
     """
     self.leftDrive = phoenix6.hardware.TalonFX(1)
     self.rightDrive = phoenix6.hardware.TalonFX(2)
     self.robotDrive = wpilib.drive.DifferentialDrive(
         self.leftDrive, self.rightDrive
     )
     self.controller = wpilib.Gamepad(0)
     self.timer = wpilib.Timer()
     # We need to invert one side of the drivetrain so that positive voltages
     # result in both sides moving forward. Depending on how your robot's
     # gearbox is constructed, you might have to invert the left side instead.
     self.rightDrive.setInverted(True)
public class Robot extends TimedRobot {
  private final CANSparkMax leftDrive = new CANSparkMax(1, MotorType.kBrushless);
  private final CANSparkMax rightDrive = new CANSparkMax(2, MotorType.kBrushless);
  private final DifferentialDrive robotDrive =
    new DifferentialDrive(leftDrive::set, rightDrive::set);
  private final Gamepad controller = new Gamepad(0);
  private final Timer timer = new Timer();
private:
 // Robot drive system
 rev::CANSparkMax left{1, rev::CANSparkMax::MotorType::kBrushless};
 rev::CANSparkMax right{2, rev::CANSparkMax::MotorType::kBrushless};
 wpi::DifferentialDrive robotDrive{
   [&](double output) { left.Set(output); },
   [&](double output) { right.Set(output); }};
 wpi::Gamepad controller{0};
 wpi::Timer timer;
13class MyRobot(wpilib.TimedRobot):
14    def robotInit(self):
15        """
16        This function is called upon program startup and
17        should be used for any initialization code.
18        """
19        self.leftDrive = rev.CANSparkMax(1, rev.CANSparkMax.MotorType.kBrushless)
20        self.rightDrive = rev.CANSparkMax(2, rev.CANSparkMax.MotorType.kBrushless)
21        self.robotDrive = wpilib.drive.DifferentialDrive(
22            self.leftDrive, self.rightDrive
23        )
24        self.controller = wpilib.XboxController(0)
25        self.timer = wpilib.Timer()
26
27        # We need to invert one side of the drivetrain so that positive voltages
28        # result in both sides moving forward. Depending on how your robot's
29        # gearbox is constructed, you might have to invert the left side instead.
30        self.rightDrive.setInverted(True)
public class Robot extends TimedRobot {
   private final WPI_TalonSRX leftDrive = new WPI_TalonSRX(1);
   private final WPI_TalonSRX rightDrive = new WPI_TalonSRX(2);
   private final DifferentialDrive robotDrive = new DifferentialDrive(leftDrive1::set, rightDrive2::set);
   private final Gamepad controller = new Gamepad(0);
   private final Timer timer = new Timer();
private:
 // Robot drive system
 ctre::phoenix::motorcontrol::can::WPI_TalonSRX left{1};
 ctre::phoenix::motorcontrol::can::WPI_TalonSRX right{2};
 wpi::DifferentialDrive robotDrive{
   [&](double output) { left.Set(output); },
   [&](double output) { right.Set(output); }};
 wpi::Gamepad controller{0};
 wpi::Timer timer;
13class MyRobot(wpilib.TimedRobot):
14    def robotInit(self):
15        """
16        This function is called upon program startup and
17        should be used for any initialization code.
18        """
19        self.leftDrive = ctre.WPI_TalonFX(1)
20        self.rightDrive = ctre.WPI_TalonFX(2)
21        self.robotDrive = wpilib.drive.DifferentialDrive(
22            self.leftDrive, self.rightDrive
23        )
24        self.controller = wpilib.XboxController(0)
25        self.timer = wpilib.Timer()
26
27        # We need to invert one side of the drivetrain so that positive voltages
28        # result in both sides moving forward. Depending on how your robot's
29        # gearbox is constructed, you might have to invert the left side instead.
30        self.rightDrive.setInverted(True)

The sample robot in our examples will have an Xbox Controller (or other Gamepad) on USB port 0 for arcade drive and two motors on PWM ports 0 and 1 (Vendor examples use CAN with IDs 1 and 2). Here we create objects of type DifferentialDrive (robotDrive), Gamepad (controller) and Timer (timer). This section of the code does three things:

  1. Defines the variables as members of our Robot class.

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

27  /** Called once at the beginning of the robot program. */
28  public Robot() {
29    // We need to invert one side of the drivetrain so that positive voltages
30    // result in both sides moving forward. Depending on how your robot's
31    // gearbox is constructed, you might have to invert the left side instead.
32    rightDrive.setInverted(true);
33  }
12 public:
13  Robot() {
14    // We need to invert one side of the drivetrain so that positive voltages
15    // result in both sides moving forward. Depending on how your robot's
16    // gearbox is constructed, you might have to invert the left side instead.
17    right.SetInverted(true);
18    robotDrive.SetExpiration(100_ms);
19    timer.Start();
20  }
def robotInit(self):

The Robot constructor for our sample program inverts the right side of the drivetrain. Depending on your drive setup, you might need to invert the left side instead.

Simple Autonomous Example

38  /** This function is run once each time the robot enters autonomous mode. */
39  @Override
40  public void autonomousInit() {
41    timer.restart();
42  }
43
44  /** This function is called periodically during autonomous. */
45  @Override
46  public void autonomousPeriodic() {
47    // Drive for 2 seconds
48    if (timer.get() < 2.0) {
49      // Drive forwards half velocity, make sure to turn input squaring off
50      robotDrive.arcadeDrive(0.5, 0.0, false);
51    } else {
52      robotDrive.stopMotor(); // stop robot
53    }
54  }
25  void AutonomousInit() override { timer.Restart(); }
26
27  void AutonomousPeriodic() override {
28    // Drive for 2 seconds
29    if (timer.Get() < 2_s) {
30      // Drive forwards half velocity, make sure to turn input squaring off
31      robotDrive.ArcadeDrive(0.5, 0.0, false);
32    } else {
33      // Stop robot
34      robotDrive.ArcadeDrive(0.0, 0.0, false);
35    }
36  }
29    def autonomousInit(self):
30        """This function is run once each time the robot enters autonomous mode."""
31        self.timer.restart()
32
33    def autonomousPeriodic(self):
34        """This function is called periodically during autonomous."""
35
36        # Drive for two seconds
37        if self.timer.get() < 2.0:
38            # Drive forwards half velocity, make sure to turn input squaring off
39            self.robotDrive.arcadeDrive(0.5, 0, squareInputs=False)
40        else:
41            self.robotDrive.stopMotor()  # Stop robot

The AutonomousInit method is run once each time the robot transitions to autonomous from another mode. In this program, we restart the Timer 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    robotDrive.arcadeDrive(-controller.getLeftY(), -controller.getRightX());
64  }
38  void TeleopInit() override {}
39
40  void TeleopPeriodic() override {
41    // Drive with arcade style (use right stick to steer)
42    robotDrive.ArcadeDrive(-controller.GetLeftY(), controller.GetRightX());
43  }
44
45  void UtilityInit() override {}
43    def teleopInit(self):
44        """This function is called once each time the robot enters teleoperated mode."""
45
46    def teleopPeriodic(self):
47        """This function is called periodically during teleoperated mode."""
48        self.robotDrive.arcadeDrive(
49            -self.controller.getLeftY(), -self.controller.getRightX()
50        )

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 left thumbstick of the Gamepad to forward/back motion of the drive motors and the X-axis to turning motion.

Utility Mode

66  /** This function is called once each time the robot enters utility mode. */
67  @Override
68  public void utilityInit() {}
69
70  /** This function is called periodically during utility mode. */
71  @Override
72  public void utilityPeriodic() {}
73}
45  void UtilityInit() override {}
46
47  void UtilityPeriodic() override {}
52    def utilityInit(self):
53        """This function is called once each time the robot enters utility mode."""
54
55    def utilityPeriodic(self):
56        """This function is called periodically during utility mode."""

Utility Mode is used for testing robot functionality or running other code that shouldn’t be run in a match. Similar to TeleopInit, the UtilityInit and UtilityPeriodic methods are provided here for illustrative purposes only.

Deploying the Project to a Robot

In Visual Studio Code, click the WPILib logo in the top right to launch the WPILib Command Palette. Select Deploy Robot Code to deploy the code to the robot.

Note

The run button in VS Code’s debug view is not used to run robot code. Instead, use the Deploy Robot Code command as described above. The debug view’s run button is used for running and debugging code on the local machine in simulation, which is not applicable for robot code that runs on Systemcore.

For more detailed instructions, see Deploy Java/C++ code.

In the terminal, run the following command to deploy the code to the robot:

py -3 -m robotpy deploy
python3 -m robotpy deploy
python3 -m robotpy deploy

For more detailed instructions, see Deploy Python code.