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.
Importante
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++)
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.
Nota
Any errors in project generation will appear in the bottom right-hand corner of the screen.
Aviso
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.
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.
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 therobotpy sync
command.The
robot.py
file is where you will put the your Robot class.
Veja também
Basic Drivetrain example
First, here is what a simple code can look like for a Drivetrain with PWM controlled motors (such as SparkMax).
Nota
the Python example below is from https://github.com/robotpy/examples/tree/main/GettingStarted
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 edu.wpi.first.wpilibj.examples.gettingstarted;
6
7import edu.wpi.first.util.sendable.SendableRegistry;
8import edu.wpi.first.wpilibj.TimedRobot;
9import edu.wpi.first.wpilibj.Timer;
10import edu.wpi.first.wpilibj.XboxController;
11import edu.wpi.first.wpilibj.drive.DifferentialDrive;
12import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
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 m_leftDrive = new PWMSparkMax(0);
21 private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
22 private final DifferentialDrive m_robotDrive =
23 new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
24 private final XboxController m_controller = new XboxController(0);
25 private final Timer m_timer = new Timer();
26
27 /** Called once at the beginning of the robot program. */
28 public Robot() {
29 SendableRegistry.addChild(m_robotDrive, m_leftDrive);
30 SendableRegistry.addChild(m_robotDrive, m_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 m_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 m_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 (m_timer.get() < 2.0) {
49 // Drive forwards half speed, make sure to turn input squaring off
50 m_robotDrive.arcadeDrive(0.5, 0.0, false);
51 } else {
52 m_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 m_robotDrive.arcadeDrive(-m_controller.getLeftY(), -m_controller.getRightX());
64 }
65
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}
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 <frc/TimedRobot.h>
6#include <frc/Timer.h>
7#include <frc/XboxController.h>
8#include <frc/drive/DifferentialDrive.h>
9#include <frc/motorcontrol/PWMSparkMax.h>
10
11class Robot : public frc::TimedRobot {
12 public:
13 Robot() {
14 wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
15 wpi::SendableRegistry::AddChild(&m_robotDrive, &m_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 m_right.SetInverted(true);
21 m_robotDrive.SetExpiration(100_ms);
22 m_timer.Start();
23 }
24
25 void AutonomousInit() override { m_timer.Restart(); }
26
27 void AutonomousPeriodic() override {
28 // Drive for 2 seconds
29 if (m_timer.Get() < 2_s) {
30 // Drive forwards half speed, make sure to turn input squaring off
31 m_robotDrive.ArcadeDrive(0.5, 0.0, false);
32 } else {
33 // Stop robot
34 m_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 m_robotDrive.ArcadeDrive(-m_controller.GetLeftY(),
43 m_controller.GetRightX());
44 }
45
46 void TestInit() override {}
47
48 void TestPeriodic() override {}
49
50 private:
51 // Robot drive system
52 frc::PWMSparkMax m_left{0};
53 frc::PWMSparkMax m_right{1};
54 frc::DifferentialDrive m_robotDrive{
55 [&](double output) { m_left.Set(output); },
56 [&](double output) { m_right.Set(output); }};
57
58 frc::XboxController m_controller{0};
59 frc::Timer m_timer;
60};
61
62#ifndef RUNNING_FRC_TESTS
63int main() {
64 return frc::StartRobot<Robot>();
65}
66#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
9import wpilib.drive
10
11
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)
30
31 def autonomousInit(self):
32 """This function is run once each time the robot enters autonomous mode."""
33 self.timer.restart()
34
35 def autonomousPeriodic(self):
36 """This function is called periodically during autonomous."""
37
38 # Drive for two seconds
39 if self.timer.get() < 2.0:
40 # Drive forwards half speed, make sure to turn input squaring off
41 self.robotDrive.arcadeDrive(0.5, 0, squareInputs=False)
42 else:
43 self.robotDrive.stopMotor() # Stop robot
44
45 def teleopInit(self):
46 """This function is called once each time the robot enters teleoperated mode."""
47
48 def teleopPeriodic(self):
49 """This function is called periodically during teleoperated mode."""
50 self.robotDrive.arcadeDrive(
51 -self.controller.getLeftY(), -self.controller.getRightX()
52 )
53
54 def testInit(self):
55 """This function is called once each time the robot enters test mode."""
56
57 def testPeriodic(self):
58 """This function is called periodically during test mode."""
59
60
61if __name__ == "__main__":
62 wpilib.run(MyRobot)
Now let’s look at various parts of the code.
Imports/Includes
1import edu.wpi.first.util.sendable.SendableRegistry;
2import edu.wpi.first.wpilibj.TimedRobot;
3import edu.wpi.first.wpilibj.Timer;
4import edu.wpi.first.wpilibj.XboxController;
5import edu.wpi.first.wpilibj.drive.DifferentialDrive;
6import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
5#include <frc/TimedRobot.h>
6#include <frc/Timer.h>
7#include <frc/XboxController.h>
8#include <frc/drive/DifferentialDrive.h>
9#include <frc/motorcontrol/PWMSparkMax.h>
8import wpilib
9import wpilib.drive
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import com.ctre.phoenix6.hardware.TalonFX;
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/XboxController.h>
#include <frc/drive/DifferentialDrive.h>
#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 edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/XboxController.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/motorcontrol/PWMSparkMax.h>
#include <rev/CANSparkMax.h>
import wpilib # Used to get the joysticks
import wpilib.drive # Used for the DifferentialDrive class
import rev # REV library
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/XboxController.h>
#include <frc/drive/DifferentialDrive.h>
#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 XBoxController
(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 Xbox controller to the motors).
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 =
23 new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
24 private final XboxController m_controller = new XboxController(0);
25 private final Timer m_timer = new Timer();
50 private:
51 // Robot drive system
52 frc::PWMSparkMax m_left{0};
53 frc::PWMSparkMax m_right{1};
54 frc::DifferentialDrive m_robotDrive{
55 [&](double output) { m_left.Set(output); },
56 [&](double output) { m_right.Set(output); }};
57
58 frc::XboxController m_controller{0};
59 frc::Timer m_timer;
60};
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 m_leftDrive = new TalonFX(1);
private final TalonFX m_rightDrive = new TalonFX(2);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
private final XboxController m_controller = new XboxController(0);
private final Timer m_timer = new Timer();
12 public:
13 Robot() {
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 m_right.SetInverted(true);
21 m_robotDrive.SetExpiration(100_ms);
22 m_timer.Start();
23 }
private:
// Robot drive system
ctre::phoenix6::hardware::TalonFX m_left{1};
ctre::phoenix6::hardware::TalonFX m_right{2};
frc::DifferentialDrive m_robotDrive{
[&](double output) { m_left.Set(output); },
[&](double output) { m_right.Set(output); }};
frc::XboxController m_controller{0};
frc::Timer m_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.XboxController(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 m_leftDrive = new CANSparkMax(1, MotorType.kBrushless);
private final CANSparkMax m_rightDrive = new CANSparkMax(2, MotorType.kBrushless);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
private final XboxController m_controller = new XboxController(0);
private final Timer m_timer = new Timer();
12 public:
13 Robot() {
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 m_right.SetInverted(true);
21 m_robotDrive.SetExpiration(100_ms);
22 m_timer.Start();
23 }
private:
// Robot drive system
rev::CANSparkMax m_left{1, rev::CANSparkMax::MotorType::kBrushless};
rev::CANSparkMax m_right{2, rev::CANSparkMax::MotorType::kBrushless};
frc::DifferentialDrive m_robotDrive{
[&](double output) { m_left.Set(output); },
[&](double output) { m_right.Set(output); }};
frc::XboxController m_controller{0};
frc::Timer m_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 m_leftDrive = new WPI_TalonSRX(1);
private final WPI_TalonSRX m_rightDrive = new WPI_TalonSRX(2);
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive1::set, m_rightDrive2::set);
private final XboxController m_controller = new XboxController(0);
private final Timer m_timer = new Timer();
12 public:
13 Robot() {
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 m_right.SetInverted(true);
21 m_robotDrive.SetExpiration(100_ms);
22 m_timer.Start();
23 }
private:
// Robot drive system
ctre::phoenix::motorcontrol::can::WPI_TalonSRX m_left{1};
ctre::phoenix::motorcontrol::can::WPI_TalonSRX m_right{2};
frc::DifferentialDrive m_robotDrive{
[&](double output) { m_left.Set(output); },
[&](double output) { m_right.Set(output); }};
frc::XboxController m_controller{0};
frc::Timer m_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 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
(m_robotDrive), XboxController
(m_controller) and Timer
(m_timer). This section of the code does three things:
Defines the variables as members of our Robot class.
Initializes the variables.
Nota
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 m_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 m_right.SetInverted(true);
18 m_robotDrive.SetExpiration(100_ms);
19 m_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 m_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 (m_timer.get() < 2.0) {
49 // Drive forwards half speed, make sure to turn input squaring off
50 m_robotDrive.arcadeDrive(0.5, 0.0, false);
51 } else {
52 m_robotDrive.stopMotor(); // stop robot
53 }
54 }
25 void AutonomousInit() override { m_timer.Restart(); }
26
27 void AutonomousPeriodic() override {
28 // Drive for 2 seconds
29 if (m_timer.Get() < 2_s) {
30 // Drive forwards half speed, make sure to turn input squaring off
31 m_robotDrive.ArcadeDrive(0.5, 0.0, false);
32 } else {
33 // Stop robot
34 m_robotDrive.ArcadeDrive(0.0, 0.0, false);
35 }
36 }
31 def autonomousInit(self):
32 """This function is run once each time the robot enters autonomous mode."""
33 self.timer.restart()
34
35 def autonomousPeriodic(self):
36 """This function is called periodically during autonomous."""
37
38 # Drive for two seconds
39 if self.timer.get() < 2.0:
40 # Drive forwards half speed, make sure to turn input squaring off
41 self.robotDrive.arcadeDrive(0.5, 0, squareInputs=False)
42 else:
43 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 m_robotDrive.arcadeDrive(-m_controller.getLeftY(), -m_controller.getRightX());
64 }
38 void TeleopInit() override {}
39
40 void TeleopPeriodic() override {
41 // Drive with arcade style (use right stick to steer)
42 m_robotDrive.ArcadeDrive(-m_controller.GetLeftY(),
43 m_controller.GetRightX());
44 }
45 def teleopInit(self):
46 """This function is called once each time the robot enters teleoperated mode."""
47
48 def teleopPeriodic(self):
49 """This function is called periodically during teleoperated mode."""
50 self.robotDrive.arcadeDrive(
51 -self.controller.getLeftY(), -self.controller.getRightX()
52 )
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 XBoxController
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 {}
54 def testInit(self):
55 """This function is called once each time the robot enters test mode."""
56
57 def testPeriodic(self):
58 """This function is called periodically during test mode."""
Test Mode is used for testing robot functionality. Similar to TeleopInit
, the TestInit
and TestPeriodic
methods are provided here for illustrative purposes only.