[examples] Add differential drive snippets (#8927)

Shows tank, arcade, and curvature for wpilib-docs
This commit is contained in:
sciencewhiz
2026-05-29 15:00:12 -07:00
committed by GitHub
parent e728ee27f2
commit 40fdb779d8
6 changed files with 123 additions and 0 deletions

View File

@@ -58,6 +58,7 @@ SNIPPET_FOLDERS = [
"AnalogPotentiometer",
"AprilTagsVision",
"CANPDP",
"DifferentialDrive",
"DigitalCommunication",
"DigitalInput",
"DutyCycleEncoder",

View File

@@ -0,0 +1,55 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "wpi/drive/DifferentialDrive.hpp"
#include "wpi/driverstation/Gamepad.hpp"
#include "wpi/framework/TimedRobot.hpp"
#include "wpi/hardware/motor/PWMSparkMax.hpp"
/**
* DifferentialDrive snippets for wpilib-docs. Runs the motors with tank
* drive, arcade drive, and curvature drive.
* https://docs.wpilib.org/en/stable/docs/software/hardware-apis/motors/wpi-drive-classes.html
*/
class Robot : public wpi::TimedRobot {
wpi::PWMSparkMax leftMotor{0};
wpi::PWMSparkMax rightMotor{1};
wpi::DifferentialDrive robotDrive{
[&](double output) { leftMotor.SetThrottle(output); },
[&](double output) { rightMotor.SetThrottle(output); }};
wpi::Gamepad driverController{0};
public:
Robot() {
// 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.
rightMotor.SetInverted(true);
}
void TeleopPeriodic() override {
// Drive with split arcade style
// That means that the Y axis of the left stick moves forward
// and backward, and the X of the right stick turns left and right.
robotDrive.ArcadeDrive(-driverController.GetLeftY(),
-driverController.GetRightX());
// Tank drive with a given left and right rates
robotDrive.TankDrive(-driverController.GetLeftY(),
-driverController.GetRightY());
// Arcade drive with a given forward and turn rate
robotDrive.ArcadeDrive(-driverController.GetLeftY(),
-driverController.GetLeftX());
// Curvature drive with a given forward and turn rate, as well as a
// quick-turn button
robotDrive.CurvatureDrive(-driverController.GetLeftY(),
-driverController.GetLeftX(),
driverController.GetFaceUpButton());
}
};
#ifndef RUNNING_WPILIB_TESTS
int main() {
return wpi::StartRobot<Robot>();
}
#endif

View File

@@ -303,5 +303,16 @@
],
"foldername": "Solenoid",
"gradlebase": "cpp"
},
{
"name": "Differential Drive",
"description": "Show differential drive control with tank, arcade, and curvature drive in teleop",
"tags": [
"Differential Drive",
"Gamepad"
],
"foldername": "DifferentialDrive",
"gradlebase": "java",
"robotclass": "Robot"
}
]

View File

@@ -59,6 +59,7 @@ SNIPPET_FOLDERS = [
"analogpotentiometer",
"apriltagsvision",
"canpdp",
"differentialdrive",
"digitalcommunication",
"digitalinput",
"dutycycleencoder",

View File

@@ -0,0 +1,44 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package org.wpilib.snippets.differentialdrive;
import org.wpilib.drive.DifferentialDrive;
import org.wpilib.driverstation.Gamepad;
import org.wpilib.framework.TimedRobot;
import org.wpilib.hardware.motor.PWMSparkMax;
/**
* DifferentialDrive snippets for wpilib-docs. Runs the motors with tank drive, arcade drive, and
* curvature drive.
* https://docs.wpilib.org/en/stable/docs/software/hardware-apis/motors/wpi-drive-classes.html
*/
public class Robot extends TimedRobot {
private final PWMSparkMax leftMotor = new PWMSparkMax(0);
private final PWMSparkMax rightMotor = new PWMSparkMax(1);
private final DifferentialDrive robotDrive =
new DifferentialDrive(leftMotor::setThrottle, rightMotor::setThrottle);
private final Gamepad driverController = new Gamepad(0);
/** Called once at the beginning of the robot program. */
public Robot() {
// 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.
rightMotor.setInverted(true);
}
@Override
public void teleopPeriodic() {
// Tank drive with a given left and right rates
robotDrive.tankDrive(-driverController.getLeftY(), -driverController.getRightY());
// Arcade drive with a given forward and turn rate
robotDrive.arcadeDrive(-driverController.getLeftY(), -driverController.getLeftX());
// Curvature drive with a given forward and turn rate, as well as a button for turning in-place.
robotDrive.curvatureDrive(
-driverController.getLeftY(),
-driverController.getLeftX(),
driverController.getFaceUpButton());
}
}

View File

@@ -332,5 +332,16 @@
"foldername": "solenoid",
"gradlebase": "java",
"robotclass": "Robot"
},
{
"name": "Differential Drive",
"description": "Show differential drive control with tank, arcade, and curvature drive in teleop",
"tags": [
"Differential Drive",
"Gamepad"
],
"foldername": "differentialdrive",
"gradlebase": "java",
"robotclass": "Robot"
}
]