Documentation Index
Fetch the complete documentation index at: https://mintlify.com/wpilibsuite/allwpilib/llms.txt
Use this file to discover all available pages before exploring further.
This is the simplest example of a working robot program. It demonstrates:
- Basic robot structure using
TimedRobot
- Setting up a differential drive with two motors
- Autonomous mode with timed driving
- Teleoperated mode with joystick control
- Proper motor inversion for drivetrain
Complete Example
package edu.wpi.first.wpilibj.examples.gettingstarted;
import edu.wpi.first.util.sendable.SendableRegistry;
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 edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class Robot extends TimedRobot {
private final PWMSparkMax m_leftDrive = new PWMSparkMax(0);
private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
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();
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftDrive);
SendableRegistry.addChild(m_robotDrive, m_rightDrive);
// 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.
m_rightDrive.setInverted(true);
}
@Override
public void autonomousInit() {
m_timer.restart();
}
@Override
public void autonomousPeriodic() {
// Drive for 2 seconds
if (m_timer.get() < 2.0) {
// Drive forwards half speed, make sure to turn input squaring off
m_robotDrive.arcadeDrive(0.5, 0.0, false);
} else {
m_robotDrive.stopMotor(); // stop robot
}
}
@Override
public void teleopPeriodic() {
m_robotDrive.arcadeDrive(-m_controller.getLeftY(), -m_controller.getRightX());
}
}
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/XboxController.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/motorcontrol/PWMSparkMax.h>
class Robot : public frc::TimedRobot {
public:
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right);
// 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.
m_right.SetInverted(true);
m_robotDrive.SetExpiration(100_ms);
m_timer.Start();
}
void AutonomousInit() override { m_timer.Restart(); }
void AutonomousPeriodic() override {
// Drive for 2 seconds
if (m_timer.Get() < 2_s) {
// Drive forwards half speed, make sure to turn input squaring off
m_robotDrive.ArcadeDrive(0.5, 0.0, false);
} else {
// Stop robot
m_robotDrive.ArcadeDrive(0.0, 0.0, false);
}
}
void TeleopPeriodic() override {
// Drive with arcade style (use right stick to steer)
m_robotDrive.ArcadeDrive(-m_controller.GetLeftY(),
m_controller.GetRightX());
}
private:
// Robot drive system
frc::PWMSparkMax m_left{0};
frc::PWMSparkMax m_right{1};
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;
};
#ifndef RUNNING_FRC_TESTS
int main() {
return frc::StartRobot<Robot>();
}
#endif
What This Example Demonstrates
Robot Structure
The robot extends TimedRobot, which automatically calls methods at 20ms intervals:
autonomousInit() - Called once when autonomous starts
autonomousPeriodic() - Called every 20ms during autonomous
teleopPeriodic() - Called every 20ms during teleoperated mode
Differential Drive
The DifferentialDrive class simplifies controlling a tank-style drivetrain:
- Takes two motor controllers (left and right)
- Provides
arcadeDrive() method for single-stick driving
- Forward/backward on one axis, turning on another
Motor Inversion
One side of the drivetrain must be inverted so both sides drive forward with positive values. This is done with setInverted(true) on the right motor.
Running in Simulation
- Deploy the code to your robot or simulator
- Enable autonomous mode to see the 2-second forward drive
- Switch to teleoperated mode and use an Xbox controller:
- Left stick Y-axis: forward/backward
- Right stick X-axis: turning
Source Location
- Java:
wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
- C++:
wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp