Drivetrain#
Introduction#
A drivetrain allows the robot to move continuously or for set distances, rotate by degrees or to a heading, and respond to changes in its rotational orientation.
If the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor, the drivetrain will be able to make more precise forward, reverse, and turning movements by tracking the sensor’s heading and rotation.
The Drivetrain category also includes configuration methods that let you set drive and turn speeds, define stopping behavior, apply timeouts to avoid execution stalls, and manually update the robot’s heading or rotation values. These features provide flexibility when designing autonomous behaviors or real-time adjustments.
This page uses drivetrain as the example drivetrain name. Replace it with your own configured name as needed.
Below is a list of available methods:
Actions — Move and turn the robot.
drive— Drives the robot continuously forward or in reverse using the current drive velocity.driveFor— Drives the robot forward or in reverse for a set distance.turn— Rotates the robot continuously left or right using the current turn velocity.turnFor— Rotates the robot left or right for a specified angle.turnToHeading— Rotates the robot to face a specific absolute heading.turnToRotation— Rotates the robot to reach a specific cumulative rotation.stop— Stops the drivetrain using the configured stopping mode.calibrateDrivetrain— Calibrates the drivetrain’s configured Inertial Sensor, GPS Sensor, or Gyro Sensor.arcade— Drives the drivetrain forward or reverse while turning at the same time.
Mutators — Set default movement and turn speeds.
setDriveVelocity— Sets the default drive velocity used by drive methods.setTurnVelocity— Sets the default turn velocity used by turn methods.setStopping— Sets how the drivetrain behaves when it stops.setTimeout— Sets how long drive and turn methods try to reach their target before timing out.setHeading— Manually sets the robot’s heading value.setRotation— Manually sets the robot’s cumulative rotation value.setGearRatio— Sets the gear ratio for all motors on the drivetrain.setTurnThreshold— Sets the turn threshold for a drivetrain.setTurnConstant— Sets the turn constant for a drivetrain.setTurnDirectionReverse— Sets a drivetrain to have its direction be reversed.setTurnVelocityMin— Sets the minimum turning velocity used by a drivetrain.
Getters — Return robot state and position.
isDone— Returns whether a drivetrain is not currently moving.isMoving— Returns whether a drivetrain is currently moving.isTurning— Returns whether a drivetrain is currently turning.heading— Returns the drivetrain’s heading angle.rotation— Returns how much the drivetrain has turned since the project started.velocity— Returns the drivetrain’s current velocity.current— Returns the drivetrain’s current draw.power— Returns the drivetrain’s power usage.torque— Returns the drivetrain’s torque.efficiency— Returns the drivetrain’s efficiency.temperature— Returns the drivetrain motors’ temperature.voltage— Returns the voltage currently applied to the drivetrain.
Constructors — Manually initialize and configure the drivetrain.
drivetrain— Creates a drivetrain without an Inertial Sensor, GPS Sensor, or Gyro Sensor.smartdrive— Creates a drivetrain configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor.
Actions#
drive#
drive moves the drivetrain forward or in reverse using the current drive velocity. This method runs continuously until another Drivetrain method interrupts it or the project stops.
Default Usage:
Drivetrain.drive(direction);
Overload Usages:
Drivetrain.drive(direction, velocity, units);
Parameters |
Description |
|---|---|
|
The direction in which the robot drives:
|
|
The velocity at which the drivetrain will move as a double. If the velocity is not specified or previously set, the default velocity is 50%. |
|
The unit to represent the velocity:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Drive forward and back
Drivetrain.drive(forward);
wait(2, seconds);
Drivetrain.drive(reverse, 25, velocityUnits::pct);
wait(2, seconds);
Drivetrain.stop();
}
driveFor#
driveFor moves the drivetrain forward or in reverse for a specified distance using the current drive velocity.
Default Usage:
Drivetrain.driveFor(direction, distance, units, wait);
Overload Usages:
Drivetrain.driveFor(direction, distance, units, velocity, units_v, wait);
Drivetrain.driveFor(distance, units, wait);
Drivetrain.driveFor(distance, units, velocity, units_v, wait);
Parameters |
Description |
|---|---|
|
The direction in which the robot drives:
|
|
The distance the drivetrain will move as a double. |
|
The units representing the distance:
|
|
Optional.
|
|
The velocity at which the drivetrain will move as a double. If the velocity is not specified or previously set, the default velocity is 50%. |
|
The unit to represent the velocity:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Drive 200 mm, then back 200 mm
Drivetrain.driveFor(forward, 200, mm);
Drivetrain.driveFor(reverse, 200, mm);
}
turn#
turn turns the drivetrain left or right indefinitely.
Default Usage:
Drivetrain.turn(direction);
Overload Usages:
Drivetrain.turn(direction, velocity, units);
Parameters |
Description |
|---|---|
|
The direction in which to turn:
|
|
The velocity at which the drivetrain will turn as a double. If the velocity is not specified or previously set, the default velocity is 50%. |
|
The unit that represents the velocity:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Turn right, then left, then stop
Drivetrain.turn(right);
wait(2, seconds);
Drivetrain.turn(left);
wait(2, seconds);
Drivetrain.stop();
}
turnFor#
turnFor turns the drivetrain left or right for a set distance.
Default Usage:
Drivetrain.turnFor(direction, angle, units, wait);
Overload Usages:
Drivetrain.turnFor(direction, angle, units, velocity, units_v, wait);
Drivetrain.turnFor(angle, units, wait);
Drivetrain.turnFor(angle, units, velocity, units_v, wait);
Parameters |
Description |
|---|---|
|
The direction in which to turn:
|
|
The amount of degrees the drivetrain will turn as a double. |
|
The unit that represents the rotational value:
|
|
The velocity at which the drivetrain will turn as a double. If the velocity is not specified or previously set, the default velocity is 50%. |
|
The unit that represents the velocity:
|
|
Optional.
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Turn right then left
Drivetrain.turnFor(right, 90, degrees);
wait(1, seconds);
Drivetrain.turnFor(left, 90, degrees);
}
turnToHeading#
turnToHeading turns a smart drivetrain to a specified heading.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Default Usage:
Drivetrain.turnToHeading(angle, units, wait);
Overload Usages:
Drivetrain.turnToHeading(angle, units, velocity, units_v, wait);
Parameters |
Description |
|---|---|
|
The heading to turn the drivetrain to face as a double. |
|
The unit that represents the rotational value:
|
|
The velocity at which the drivetrain will spin as a double. If the velocity is not specified or previously set, the default velocity is 50%. |
|
The unit that represents the velocity:
|
|
Optional.
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Face the cardinal directions
Drivetrain.turnToHeading(90, degrees);
wait(1, seconds);
Drivetrain.turnToHeading(180, degrees);
wait(1, seconds);
Drivetrain.turnToHeading(270, degrees);
wait(1, seconds);
Drivetrain.turnToHeading(0, degrees);
}
turnToRotation#
turnToRotation turns a smart drivetrain to a specified rotational value.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Default Usage:
Drivetrain.turnToRotation(angle, units, wait);
Overload Usages:
Drivetrain.turnToRotation(angle, units, velocity, units_v, wait);
Parameters |
Description |
|---|---|
|
The rotational value to turn the drivetrain to face as a double. |
|
The unit that represents the rotational value:
|
|
The velocity at which the drivetrain will spin as a double. If the velocity is not specified or previously set, the default velocity is 50%. |
|
The unit that represents the velocity:
|
|
Optional.
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Turn left, then spin clockwise to face right
Drivetrain.turnToRotation(-90, degrees);
wait(1, seconds);
Drivetrain.turnToRotation(450, degrees);
}
stop#
stop stops a drivetrain.
Default Usage:
Drivetrain.stop();
Overload Usages:
Drivetrain.stop(mode);
Parameters |
Description |
|---|---|
|
The stopping behavior to use when the drivetrain stops:
brake. |
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Drive forward, then coast to a stop
Drivetrain.setDriveVelocity(100, percent);
Drivetrain.drive(forward);
wait(2, seconds);
Drivetrain.stop(coast);
}
calibrateDrivetrain#
calibrateDrivetrain calibrates the drivetrain.
This is a method generated by the VEXcode Robot Configuration when a drivetrain is configured in the Devices window. It will not function outside of VEXcode V5.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.calibrateDrivetrain();
Parameters |
Description |
|---|---|
This method has no parameters. |
arcade#
arcade moves the drivetrain forward or reverse while turning at the same time. This method runs continuously until another Drivetrain method interrupts it or the project stops.
Usage:
Drivetrain.arcade(drivePower, turnPower, units);
Parameters |
Description |
|---|---|
|
The velocity to move forward or reverse as a double. A positive number will move forward, negative will move reverse. |
|
The velocity to turn left or right as a double. A positive number will turn right, negative will turn left. |
|
Optional. The unit that represents the power values:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Drive forward and left for 2 seconds
Drivetrain.arcade(25, -25);
wait(2, seconds);
Drivetrain.driveFor(forward, 12, inches);
}
Mutators#
setDriveVelocity#
setDriveVelocity sets the default moving velocity for a drivetrain. This velocity setting will be used for subsequent calls to any drivetrain functions if a specific velocity is not provided.
Usage:
Drivetrain.setDriveVelocity(velocity, units);
Parameters |
Description |
|---|---|
|
The velocity at which the drivetrain will move as a double. |
|
The unit that represents the velocity:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Try default, slow, then fast
Drivetrain.driveFor(forward, 150, mm);
wait(1, seconds);
Drivetrain.setDriveVelocity(20, percent);
Drivetrain.driveFor(forward, 150, mm);
wait(1, seconds);
Drivetrain.setDriveVelocity(100, percent);
Drivetrain.driveFor(forward, 150, mm);
}
setTurnVelocity#
setTurnVelocity sets the default turning velocity for a drivetrain. This velocity setting will be used for subsequent calls to any drivetrain functions if a specific velocity is not provided.
Usage:
Drivetrain.setTurnVelocity(velocity, units);
Parameters |
Description |
|---|---|
|
The velocity at which the drivetrain will turn as a double. |
|
The unit that represents the velocity:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Try default, slow, then fast
Drivetrain.turnFor(right, 360, degrees);
wait(1, seconds);
Drivetrain.setTurnVelocity(20, percent);
Drivetrain.turnFor(right, 360, degrees);
wait(1, seconds);
Drivetrain.setTurnVelocity(100, percent);
Drivetrain.turnFor(right, 360, degrees);
}
setStopping#
setStopping sets the stopping mode for a drivetrain.
Usage:
Drivetrain.setStopping(mode);
Parameters |
Description |
|---|---|
|
How the drivetrain will stop:
|
setTimeout#
setTimeout sets a time limit for how long a Drivetrain command will wait to reach its target. If the robot cannot complete the movement within the set time, it will stop automatically and continue with the next command.
Note: The drivetrain’s time limit is used to prevent Drivetrain commands that do not reach their target position from stopping the execution of other commands.
Usage:
Drivetrain.setTimeout(time, units);
Parameters |
Description |
|---|---|
|
The maximum number of seconds a motor function will run before stopping and moving to the next function as an integer. |
|
The unit that represents the time:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Start turning if drive took too long
Drivetrain.setTimeout(1, seconds);
Drivetrain.driveFor(forward, 25, inches);
Drivetrain.turnFor(right, 90, degrees);
}
setHeading#
setHeading sets the heading of a smart drivetrain.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.setHeading(value, units);
Parameters |
Description |
|---|---|
|
The new heading as a double. |
|
The unit that represents the heading:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Face the new 0 degrees
Drivetrain.setHeading(90, degrees);
Drivetrain.turnToHeading(0, degrees);
}
setRotation#
setRotation sets the rotation for the smart drivetrain.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.setRotation(value, units);
Parameters |
Description |
|---|---|
|
The new rotational value as a double. |
|
The unit that represents the rotation:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Spin counterclockwise for 2 turns, then face forward
Drivetrain.setRotation(720, degrees);
Drivetrain.turnToRotation(0, degrees);
}
setGearRatio#
setGearRatio sets the gear ratio for all motors on the drivetrain.
Usage:
Drivetrain.setGearRatio(mode);
Parameters |
Description |
|---|---|
|
Gear Ratio options:
|
// Set 2:1 gear ratio
Drivetrain.setGearRatio(ratio2_1);
setTurnThreshold#
setTurnThreshold sets the turn threshold for a smart drivetrain. The threshold value is used to determine that turns are complete. If this is too large, then turns will not be accurate. If too small, then turns may not complete.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.setTurnThreshold(threshold);
Parameters |
Description |
|---|---|
|
The new turn threshold in |
// Increase turn threshold to 5 degrees
Drivetrain.setTurnThreshold(5);
setTurnConstant#
setTurnConstant sets the turn constant for a smart drivetrain. Smart drivetrains use a simple P controller when doing turns. This constant, generally known as kp, is the gain used in the equation that turns angular error into motor velocity.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.setTurnConstant(kp);
Parameters |
Description |
|---|---|
|
The new turn constant in the range 0.1–4.0. The default is 1.0. |
// Increase turn gain to 2.0
Drivetrain.setTurnConstant(2.0);
setTurnDirectionReverse#
setTurnDirectionReverse sets the smart drivetrain to be reversed.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.setTurnDirectionReverse(value);
Parameters |
Description |
|---|---|
|
A Boolean value to set the reversed flag to |
setTurnVelocityMin#
setTurnVelocityMin sets the minimum turning velocity used by a drivetrain. This prevents the drivetrain from slowing below a minimum speed while turning, which helps avoid stalling or incomplete turns.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.setTurnVelocityMin(velocity);
Parameters |
Description |
|---|---|
|
The minimum turning velocity as a double. |
Getters#
isDone#
isDone returns a Boolean indicating whether driveFor, turnToHeading, turnToRotation, or turnFor is not running.
true— The drivetrain is not moving towards a target.false— The drivetrain is moving towards a target.
Usage:
Drivetrain.isDone()
Parameters |
Description |
|---|---|
This method has no parameters. |
isMoving#
isMoving returns a Boolean indicating whether driveFor, turnToHeading, turnToRotation, or turnFor is still running.
true— The drivetrain is moving towards a target.false— The drivetrain is not moving towards a target.
Usage:
Drivetrain.isMoving()
Parameters |
Description |
|---|---|
This method has no parameters. |
isTurning#
isTurning returns a Boolean indicating whether turnToHeading, turnToRotation, or turnFor is still running.
true— The drivetrain is currently rotating to a target.false— The drivetrain is not currently rotating to a target.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.isTurning()
Parameters |
Description |
|---|---|
This method has no parameters. |
heading#
heading returns the current heading of a smart drivetrain from 0–359.99 degrees as a double.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.heading(units)
Parameters |
Description |
|---|---|
|
Optional. The unit that represents the rotational value:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Display heading after a long turn
Drivetrain.turnFor(right, 450, degrees);
Brain.Screen.print("Heading: %f", Drivetrain.heading(degrees));
}
rotation#
rotation returns the current rotational value of a smart drivetrain as a double.
Note: This method is only available if the drivetrain is configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor in the Devices window.
Usage:
Drivetrain.rotation(units)
Parameters |
Description |
|---|---|
|
Optional. The unit that represents the rotational value:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Display rotation after a long turn
Drivetrain.turnFor(right, 450, degrees);
Brain.Screen.print("Rotation: %f", Drivetrain.rotation(degrees));
}
velocity#
velocity returns the current velocity of a drivetrain as a double.
Usage:
Drivetrain.velocity(units)
Parameters |
Description |
|---|---|
|
The unit that represents the velocity:
|
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Show velocity before and during motion
Brain.Screen.print("Resting: %f", Drivetrain.velocity(percent));
Drivetrain.drive(forward, 100, velocityUnits::pct);
wait(1, seconds);
Brain.Screen.newLine();
Brain.Screen.print("Moving: %f", Drivetrain.velocity(percent));
Drivetrain.stop();
}
current#
current returns the drivetrain’s current as a double.
Usage:
Drivetrain.current(units)
Parameters |
Description |
|---|---|
|
The unit that represents the current:
|
power#
power returns the average power of the smart drivetrain as a double.
Usage:
Drivetrain.power(units)
Parameters |
Description |
|---|---|
|
The unit that represents the power:
|
torque#
torque returns the average torque of the drivetrain as a double.
Usage:
Drivetrain.torque(units)
Parameters |
Description |
|---|---|
|
A valid torque Unit:
|
efficiency#
efficiency returns the average efficiency of the drivetrain as a double.
Usage:
Drivetrain.efficiency(units)
Parameters |
Description |
|---|---|
|
The unit that represents the efficiency:
|
temperature#
temperature returns the average temperature of the drivetrain as a double.
Usage:
Drivetrain.temperature(units)
Parameters |
Description |
|---|---|
|
The unit that represents the temperature:
|
voltage#
voltage returns the voltage currently applied to the drivetrain motors.
Usage:
Drivetrain.voltage(units)
Parameters |
Description |
|---|---|
|
The unit that represents the voltage:
|
Constructors#
Constructors are used to manually create drivetrain and smartdrive objects, which are necessary for configuring a drivetrain outside of VEXcode.
drivetrain#
drivetrain creates a drivetrain without an Inertial Sensor, GPS Sensor, or Gyro Sensor.
Usage:
drivetrain(l, r, wheelTravel, trackWidth, wheelBase, unit, externalGearRatio);
Parameter |
Description |
|---|---|
|
The name of the left motor or motor group. |
|
The name of the right motor or motor group. |
|
The circumference of the driven wheels as a double. The default is 320 millimeters. |
|
The track width of the drivetrain as a double. The default is 320 millimeters. |
|
The wheel base of the drivetrain as a double. The default is 130 millimeters. |
|
The units that represent
|
|
The gear ratio used to compensate drive distances if gearing is used as a double. The default is 1.0. |
Note: Motors and/or motor groups must be created first before they can be used to create an object with the drivetrain constructor.
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Create the motors
motor leftMotor = motor(PORT1, false);
motor rightMotor = motor(PORT2, true);
/*
Create a drivetrain with the following values:
wheelTravel: 259.34
trackWidth: 320
wheelBase: 40
units: MM
externalGearRatio: 1
*/
drivetrain Drivetrain = drivetrain(leftMotor, rightMotor, 259.34, 320, 40, mm, 1);
}
smartdrive#
smartdrive creates a drivetrain configured with an Inertial Sensor, GPS Sensor, or Gyro Sensor.
Usage:
smartdrive(lm, rm, guido, wheelTravel, trackWidth, wheelBase, unit, externalGearRatio);
Parameter |
Description |
|---|---|
|
The name of the left motor or motor group. |
|
The name of the right motor or motor group. |
|
The name of the Inertial Sensor, GPS Sensor, or Gyro Sensor. |
|
The circumference of the driven wheels as a double. The default is 320 millimeters. |
|
The track width of the drivetrain as a double. The default is 320 millimeters. |
|
The wheel base of the drivetrain as a double. The default is 130 millimeters. |
|
The units that represent
|
|
The gear ratio used to compensate drive distances if gearing is used as a double. The default is 1.0. |
Note: Motors and/or motor groups must be created first before they can be used to create an object with the smartdrive constructor.
int main() {
// Initializing Robot Configuration. DO NOT REMOVE!
vexcodeInit();
// Create the motors
motor leftMotor = motor(PORT1, false);
motor rightMotor = motor(PORT2, true);
// Create an Inertial sensor in Port 3
inertial myInertial = inertial(PORT3);
/*
Create a drivetrain with the following values:
wheelTravel: 259.34
trackWidth: 320
wheelBase: 40
units: MM
externalGearRatio: 1
*/
smartdrive Smartdrive = smartdrive(leftMotor, rightMotor, myInertial, 259.34, 320, 40, mm, 1);
}