Main API

Chassis

class Chassis

Chassis class.

Public Functions

void calibrate(bool calibrateIMU = true)

Calibrate the chassis sensors. THis should be called in the initialize function.

Example

// initialize function in your project. The first function that runs when the program is started
void initialize() {
    chassis.calibrate();
}
// initialize function in your project. The first function that runs when the program is started
void initialize() {
    // don't calibrate the IMU
    // this should only be necessary if you are using a different library that calibrates the IMU
    chassis.calibrate(false);
}

Parameters:

calibrateIMU – whether the IMU should be calibrated. true by default

void setPose(float x, float y, float theta, bool radians = false)

Set the pose of the chassis.

Example

// set the pose of the chassis to x = 0, y = 0, theta = 0
chassis.setPose(0, 0, 0);
// set the pose of the chassis to x = 5.3, y = 12.2, theta = 3.14
// this time with theta in radians
chassis.setPose(5.3, 12.2, 3.14, true);

Parameters:
  • x – new x value

  • y – new y value

  • theta – new theta value

  • radians – true if theta is in radians, false if not. False by default

void setPose(Pose pose, bool radians = false)

Set the pose of the chassis.

Example

// set the pose of the chassis to x = 0, y = 0, theta = 0
lemlib::Pose poseA(0, 0, 0);
chassis.setPose(poseA);
// set the pose of the chassis to x = 5.3, y = 12.2, theta = 3.14
// this time with theta in radians
lemlib::Pose poseB(5.3, 12.2, 3.14);
chassis.setPose(poseB, true);

Parameters:
  • pose – the new pose

  • radians – whether pose theta is in radians (true) or not (false). false by default

Pose getPose(bool radians = false, bool standardPos = false)

Get the pose of the chassis.

Example

// get the pose of the chassis
lemlib::Pose pose = chassis.getPose();
// print the x, y, and theta values of the pose
printf("X: %f, Y: %f, Theta: %f\n", pose.x, pose.y, pose.theta);
// get the pose of the chassis in radians
lemlib::Pose poseRad = chassis.getPose(true);
// print the x, y, and theta values of the pose
printf("X: %f, Y: %f, Theta: %f\n", poseRad.x, poseRad.y, poseRad.theta);
// get the pose of the chassis in radians and standard position
lemlib::Pose poseRadStandard = chassis.getPose(true, true);
// print the x, y, and theta values of the pose
printf("X: %f, Y: %f, Theta: %f\n", poseRadStandard.x, poseRadStandard.y, poseRadStandard.theta);

Parameters:

radians – whether theta should be in radians (true) or degrees (false). false by default

Returns:

Pose

void waitUntil(float dist)

Wait until the robot has traveled a certain distance along the path.

Example

// move the robot to x = 20, y = 15, and face heading 90
chassis.moveToPose(20, 15, 90, 4000);
// wait until the robot has traveled 10 inches
chassis.waitUntil(10);
// output "traveled 10 inches" to the console
std::cout << "traveled 10 inches" << std::endl;
// turn the robot to face 270 degrees
// this will wait for the last motion to complete before running
chassis.turnToHeading(270, 4000);
// wait until the robot has traveled 45 degrees
chassis.waitUntil(45);
// output "traveled 45 degrees" to the console
std::cout << "traveled 45 degrees" << std::endl;

Note

Units are in inches if current motion is moveToPoint, moveToPose or follow, degrees for everything else

Parameters:

dist – the distance the robot needs to travel before returning

void waitUntilDone()

Wait until the robot has completed the path.

Example

// move the robot to x = 20, y = 15, and face heading 90
chassis.moveToPose(20, 15, 90, 4000);
// wait until the robot has completed the motion
chassis.waitUntilDone();
// output "motion completed" to the console
std::cout << "motion completed" << std::endl;

void setBrakeMode(pros::motor_brake_mode_e mode)

Sets the brake mode of the drivetrain motors.

Example

// set the brake mode of the drivetrain motors to hold
chassis.setBrakeMode(pros::E_MOTOR_BRAKE_HOLD);
// set the brake mode of the drivetrain motors to coast
chassis.setBrakeMode(pros::E_MOTOR_BRAKE_COAST);
// set the brake mode of the drivetrain motors to brake
chassis.setBrakeMode(pros::E_MOTOR_BRAKE_BRAKE);

Parameters:

mode – Mode to set the drivetrain motors to

void turnToPoint(float x, float y, int timeout, TurnToPointParams params = {}, bool async = true)

Turn the chassis so it is facing the target point.

Example

chassis.setPose(0, 0, 0); // set the pose of the chassis to x = 0, y = 0, theta = 0
// turn the robot to face the point x = 45, y = -45, with a timeout of 1000ms
chassis.turnToPoint(45, -45, 1000);
// turn the robot to face the point x = 45, y = -45, with a timeout of 1000ms
// but face the point with the back of the robot
chassis.turnToPoint(45, -45, 1000, {.forwards = false});
// turn the robot to face the point x = -20, 32.5 with a timeout of 2000ms
// and a maximum speed of 60
chassis.turnToPoint(-20, 32.5, 2000, {.maxSpeed = 60});
// turn the robot to face the point x = -30, y = 22.5 with a timeout of 1500ms
// and turn counterclockwise
chassis.turnToPoint(-30, 22.5, 1500, {.direction = AngularDirection::CCW_COUNTERCLOCKWISE});
// turn the robot to face the point x = 10, y = 10 with a timeout of 500ms
// with a minSpeed of 20 and a maxSpeed of 60
chassis.turnToPoint(10, 10, 500, {.maxSpeed = 60, .minSpeed = 20});
// turn the robot to face the point x = 7.5, y = 7.5 with a timeout of 2000ms
// and a minSpeed of 60, and exit the movement if the robot is within 5 degrees of the target
chassis.turnToPoint(7.5, 7.5, 2000, {.minSpeed = 60, .earlyExitRange = 5});

Parameters:
  • x – x location

  • y – y location

  • timeout – longest time the robot can spend moving

  • params – struct to simulate named parameters

  • async – whether the function should be run asynchronously. true by default

void turnToHeading(float theta, int timeout, TurnToHeadingParams params = {}, bool async = true)

Turn the chassis so it is facing the target heading.

Example

chassis.setPose(0, 0, 0); // set the pose of the chassis to x = 0, y = 0, theta = 0
// turn the robot to face heading 135, with a timeout of 1000ms
chassis.turnToHeading(135, 1000);
// turn the robot to face heading 230.5 with a timeout of 2000ms
// and a maximum speed of 60
chassis.turnToHeading(230.5, 2000, {.maxSpeed = 60});
// turn the robot to face heading -90 with a timeout of 1500ms
// and turn counterclockwise
chassis.turnToHeading(-90, 1500, {.direction = AngularDirection::CCW_COUNTERCLOCKWISE});
// turn the robot to face heading 90 with a timeout of 500ms
// with a minSpeed of 20 and a maxSpeed of 60
chassis.turnToHeading(90, 500, {.maxSpeed = 60, .minSpeed = 20});
// turn the robot to face heading 45 with a timeout of 2000ms
// and a minSpeed of 60, and exit the movement if the robot is within 5 degrees of the target
chassis.turnToHeading(45, 2000, {.minSpeed = 60, .earlyExitRange = 5});

Parameters:
  • theta – heading location

  • timeout – longest time the robot can spend moving

  • params – struct to simulate named parameters

  • async – whether the function should be run asynchronously. true by default

void swingToHeading(float theta, DriveSide lockedSide, int timeout, SwingToHeadingParams params = {}, bool async = true)

Turn the chassis so it is facing the target heading, but only by moving one half of the drivetrain.

Example

chassis.setPose(0, 0, 0); // set the pose of the chassis to x = 0, y = 0, theta = 0
// turn the robot to face heading 135, with a timeout of 1000ms
// and lock the left side of the drivetrain
chassis.swingToHeading(135, DriveSide::LEFT, 1000);
// turn the robot to face heading 230.5 with a timeout of 2000ms
// and a maximum speed of 60
// and lock the right side of the drivetrain
chassis.swingToHeading(230.5, DriveSide::RIGHT, 2000, {.maxSpeed = 60});
// turn the robot to face heading -90 with a timeout of 1500ms
// and turn counterclockwise
// and lock the left side of the drivetrain
chassis.swingToHeading(-90, DriveSide::LEFT, 1500, {.direction = AngularDirection::CCW_COUNTERCLOCKWISE});
// turn the robot to face heading 90 with a timeout of 500ms
// with a minSpeed of 20 and a maxSpeed of 60
// and lock the right side of the drivetrain
chassis.swingToHeading(90, DriveSide::RIGHT, 500, {.maxSpeed = 60, .minSpeed = 20});
// turn the robot to face heading 45 with a timeout of 2000ms
// and a minSpeed of 60, and exit the movement if the robot is within 5 degrees of the target
// and lock the left side of the drivetrain
chassis.swingToHeading(45, DriveSide::LEFT, 2000, {.minSpeed = 60, .earlyExitRange = 5});

Parameters:
  • theta – heading location

  • lockedSide – side of the drivetrain that is locked

  • timeout – longest time the robot can spend moving

  • params – struct to simulate named parameters

  • async – whether the function should be run asynchronously. true by default

void swingToPoint(float x, float y, DriveSide lockedSide, int timeout, SwingToPointParams params = {}, bool async = true)

Turn the chassis so it is facing the target point, but only by moving one half of the drivetrain.

Example

chassis.setPose(0, 0, 0); // set the pose of the chassis to x = 0, y = 0, theta = 0
// turn the robot to face the point x = 45, y = -45, with a timeout of 1000ms
// and lock the left side of the drivetrain
chassis.swingToPoint(45, -45, DriveSide::LEFT, 1000);
// turn the robot to face the point x = 45, y = -45, with a timeout of 1000ms
// but face the point with the back of the robot
// and lock the right side of the drivetrain
chassis.swingToPoint(45, -45, DriveSide::RIGHT, 1000, {.forwards = false});
// turn the robot to face the point x = -20, 32.5 with a timeout of 2000ms
// and a maximum speed of 60
// and lock the left side of the drivetrain
chassis.swingToPoint(-20, 32.5, DriveSide::LEFT, 2000, {.maxSpeed = 60});
// turn the robot to face the point x = -30, y = 22.5 with a timeout of 1500ms
// and turn counterclockwise
// and lock the right side of the drivetrain
chassis.swingToPoint(-30, 22.5, DriveSide::RIGHT, 1500, {.direction =
AngularDirection::CCW_COUNTERCLOCKWISE});
// turn the robot to face the point x = 10, y = 10 with a timeout of 500ms
// with a minSpeed of 20 and a maxSpeed of 60
// and lock the left side of the drivetrain
chassis.swingToPoint(10, 10, DriveSide::LEFT, 500, {.maxSpeed = 60, .minSpeed = 20});
// turn the robot to face the point x = 7.5, y = 7.5 with a timeout of 2000ms
// and a minSpeed of 60, and exit the movement if the robot is within 5 degrees of the target
// and lock the right side of the drivetrain
chassis.swingToPoint(7.5, 7.5, DriveSide::RIGHT, 2000, {.minSpeed = 60, .earlyExitRange = 5});

Parameters:
  • x – x location

  • y – y location

  • lockedSide – side of the drivetrain that is locked

  • timeout – longest time the robot can spend moving

  • params – struct to simulate named parameters

  • async – whether the function should be run asynchronously. true by default

void moveToPose(float x, float y, float theta, int timeout, MoveToPoseParams params = {}, bool async = true)

Move the chassis towards the target pose.

Uses the boomerang controller

Example

// move the robot to x = 20, y = 15, and face heading 90 with a timeout of 4000ms
chassis.moveToPose(20, 15, 90, 4000);
// move the robot to x = 20, y = 15, and face heading 90 with a timeout of 4000ms
// but face the point with the back of the robot
chassis.moveToPose(20, 15, 90, 4000, {.forwards = false});
// move the robot to x = -20, 32.5 and face heading 90 with a timeout of 4000ms
// with a maxSpeed of 60
chassis.moveToPose(-20, 32.5, 90, 4000, {.maxSpeed = 60});
// move the robot to x = 10, y = 10 and face heading 90
// with a minSpeed of 20 and a maxSpeed of 60
chassis.moveToPose(10, 10, 90, 4000, {.maxSpeed = 60, .minSpeed = 20});
// move the robot to x = 7.5, y = 7.5 and face heading 90 with a timeout of 4000ms
// with a minSpeed of 60, and exit the movement if the robot is within 5 inches of the target
chassis.moveToPose(7.5, 7.5, 90, 4000, {.minSpeed = 60, .earlyExitRange = 5});
// move the robot to 0, 0, and facing heading 0 with a timeout of 4000ms
// this motion should not be as curved as the others, so we set lead to a smaller value (0.3)
chassis.moveToPose(0, 0, 0, 4000, {.lead = 0.3});

Parameters:
  • x – x location

  • y – y location

  • theta – target heading in degrees.

  • timeout – longest time the robot can spend moving

  • params – struct to simulate named parameters

  • async – whether the function should be run asynchronously. true by default

void moveToPoint(float x, float y, int timeout, MoveToPointParams params = {}, bool async = true)

Move the chassis towards a target point.

Example

// move the robot to x = 20, y = 15 with a timeout of 4000ms
chassis.moveToPoint(20, 15, 4000);
// move the robot to x = 20, y = 15 with a timeout of 4000ms
// but face the point with the back of the robot
chassis.moveToPoint(20, 15, 4000, {.forwards = false});
// move the robot to x = -20, 32.5 with a timeout of 4000ms
// with a maxSpeed of 60
chassis.moveToPoint(-20, 32.5, 4000, {.maxSpeed = 60});
// move the robot to x = 10, y = 10 with a timeout of 4000ms
// with a minSpeed of 20 and a maxSpeed of 60
chassis.moveToPoint(10, 10, 4000, {.maxSpeed = 60, .minSpeed = 20});
// move the robot to x = 7.5, y = 7.5 with a timeout of 4000ms
// with a minSpeed of 60, and exit the movement if the robot is within 5 inches of the target
chassis.moveToPoint(7.5, 7.5, 4000, {.minSpeed = 60, .earlyExitRange = 5});

Parameters:
  • x – x location

  • y – y location

  • timeout – longest time the robot can spend moving

  • params – struct to simulate named parameters

  • async – whether the function should be run asynchronously. true by default

void follow(const asset &path, float lookahead, int timeout, bool forwards = true, bool async = true)

Move the chassis along a path.

Example

// load "myPath.txt"
// the file should be in the "static" folder in the project root directory
// this should also be done outside of any functions, otherwise it won't compile
ASSET(myPath_txt); // we replace "." with "_" to make the asset name valid

// autonomous function in your project. The function that runs during the autonomous period
void autonomous() {
    // follow the path in "myPath.txt" with a lookahead of 10 inches and a timeout of 4000ms
    chassis.follow(myPath_txt, 10, 4000);
    // follow the path in "myPath.txt" with a lookahead of 10 inches and a timeout of 4000ms
    // but follow the path backwards
    chassis.follow(myPath_txt, 10, 4000, false);
}

Parameters:
  • path – the path asset to follow

  • lookahead – the lookahead distance. Units in inches. Larger values will make the robot move faster but will follow the path less accurately

  • timeout – the maximum time the robot can spend moving

  • forwards – whether the robot should follow the path going forwards. true by default

  • async – whether the function should be run asynchronously. true by default

void tank(int left, int right, bool disableDriveCurve = false)

Control the robot during the driver using the tank drive control scheme. In this control scheme one joystick axis controls the left motors’ forward and backwards movement of the robot, while the other joystick axis controls right motors’ forward and backward movement.

Example

// opcontrol function in your project. The function that runs during the driver control period
void opcontrol() {
    // controller
    pros::Controller controller(pros::E_CONTROLLER_MASTER);
    // loop to continuously update motors
    while (true) {
        // get joystick positions
        int leftY = controller.get_analog(pros::E_CONTROLLER_ANALOG_LEFT_Y);
        int rightY = controller.get_analog(pros::E_CONTROLLER_ANALOG_RIGHT_Y);
        // move the chassis with tank controls
        chassis.tank(leftY, rightY);
        // delay to save resources
        pros::delay(25);
    }
}

Parameters:
  • left – speed to move left wheels forward or backward. Takes an input from -127 to 127.

  • right – speed to move right wheels forward or backward. Takes an input from -127 to 127.

  • disableDriveCurve – whether to disable the drive curve or not. If disabled, uses a linear curve with no deadzone or minimum power

void arcade(int throttle, int turn, bool disableDriveCurve = false, float desaturateBias = 0.5)

Control the robot during the driver using the arcade drive control scheme. In this control scheme one joystick axis controls the forwards and backwards movement of the robot, while the other joystick axis controls the robot’s turning.

Example

// opcontrol function in your project. The function that runs during the driver control period
void opcontrol() {
    // controller
    pros::Controller controller(pros::E_CONTROLLER_MASTER);
    // loop to continuously update motors
    while (true) {
        // get joystick positions
        int leftY = controller.get_analog(pros::E_CONTROLLER_ANALOG_LEFT_Y);
        int rightX = controller.get_analog(pros::E_CONTROLLER_ANALOG_RIGHT_X);
        // move the chassis with arcade controls
        chassis.arcade(leftY, // throttle
                       rightX, // steer
                       false, // enable drive curves
                       0.75 // slightly prioritize steering
        );
        // delay to save resources
        pros::delay(25);
    }
}

Parameters:
  • throttle – speed to move forward or backward. Takes an input from -127 to 127.

  • turn – speed to turn. Takes an input from -127 to 127.

  • disableDriveCurve – whether to disable the drive curve or not. If disabled, uses a linear curve with no deadzone or minimum power

  • desaturateBias – how much to favor angular motion over lateral motion or vice versa when motors are saturated. A value of 0 fully prioritizes lateral motion, a value of 1 fully prioritizes angular motion

void curvature(int throttle, int turn, bool disableDriveCurve = false)

Control the robot during the driver using the curvature drive control scheme. This control scheme is very similar to arcade drive, except the second joystick axis controls the radius of the curve that the drivetrain makes, rather than the speed. This means that the driver can accelerate in a turn without changing the radius of that turn. This control scheme defaults to arcade when forward is zero.

Example

// opcontrol function in your project. The function that runs during the driver control period
void opcontrol() {
    // controller
    pros::Controller controller(pros::E_CONTROLLER_MASTER);
    // loop to continuously update motors
    while (true) {
        // get joystick positions
        int leftY = controller.get_analog(pros::E_CONTROLLER_ANALOG_LEFT_Y);
        int rightX = controller.get_analog(pros::E_CONTROLLER_ANALOG_RIGHT_X);
        // move the chassis with curvature controls
        chassis.curvature(leftY, rightX);
        // delay to save resources
        pros::delay(25);
    }
}

Parameters:
  • throttle – speed to move forward or backward. Takes an input from -127 to 127.

  • turn – speed to turn. Takes an input from -127 to 127.

  • disableDriveCurve – whether to disable the drive curve or not. If disabled, uses a linear curve with no deadzone or minimum power

void cancelMotion()

Cancels the currently running motion. If there is a queued motion, then that queued motion will run.

Example

// move the robot to x = 20, y = 20 with a timeout of 4000ms
chassis.moveToPoint(20, 20, 4000);
// wait 500 milliseconds
pros::delay(500);
// cancel the current motion. This stops it immediately
chassis.cancelMotion();
Example (advanced)
// this example shows how the cancelMotion function behaves when a motion is queued
// this is an advanced example since we will be using tasks here
// move the robot to x = 20, y = 20 with a timeout of 4000ms
chassis.moveToPoint(20, 20, 4000);
// start a lambda task that will be used to cancel the motion after 500ms
pros::Task task([] {
    // wait 500 milliseconds
    pros::delay(500);
    // cancel the current motion. This stops it immediately
    chassis.cancelMotion();
});
// queue a motion to x = 10, y = 10 with a timeout of 4000ms
// this will run after the first motion is cancelled
chassis.moveToPoint(10, 10, 4000);

void cancelAllMotions()

Cancels all motions, even those that are queued. After this, the chassis will not be in motion.

Example

// move the robot to x = 20, y = 20 with a timeout of 4000ms
chassis.moveToPoint(20, 20, 4000);
// wait 500 milliseconds
pros::delay(500);
// cancel all motions. The robot will stop immediately
chassis.cancelAllMotions();
Example (advanced)
// this example shows how the cancelMotion function behaves when a motion is queued
// this is an advanced example since we will be using tasks here
// move the robot to x = 20, y = 20 with a timeout of 4000ms
chassis.moveToPoint(20, 20, 4000);
// start a lambda task that will be used to cancel all motions after 500ms
pros::Task task([] {
    // wait 500 milliseconds
    pros::delay(500);
    // cancels both motions
    chassis.cancelAllMotions();
});
// queue a motion to x = 10, y = 10 with a timeout of 4000ms
// this will never run because cancelAllMotions will be called while this motion is in the queue
chassis.moveToPoint(10, 10, 4000);

bool isInMotion() const

Example

// move the robot to x = 20, y = 15, and face heading 90
chassis.moveToPose(20, 15, 90, 4000);
// delay for 500ms
// this returns true, since the robot is still in motion
chassis.isInMotion();

Returns:

whether a motion is currently running

void resetLocalPosition()

Resets the x and y position of the robot without interfering with the heading.

Example

// set robot position to x = 10, y = 15, and heading 90
chassis.setPose(10, 15, 90);
// reset the robot's x and y position
chassis.resetLocalPosition();
// the robot's position is now x = 0, y = 0, and heading 90

Public Members

PID lateralPID

PIDs are exposed so advanced users can implement things like gain scheduling Changes are immediate and will affect a motion in progress

Warning

Do not interact with these unless you know what you are doing

PID angularPID

PIDs are exposed so advanced users can implement things like gain scheduling Changes are immediate and will affect a motion in progress

Warning

Do not interact with these unless you know what you are doing

Movement Options

struct TurnToPointParams

Parameters for Chassis::turnToPoint.

We use a struct to simplify customization. Chassis::turnToPoint has many parameters and specifying them all just to set one optional param ruins readability. By passing a struct to the function, we can have named parameters, overcoming the c/c++ limitation

Public Members

bool forwards = true

whether the robot should turn to face the point with the front of the robot. True by default

AngularDirection direction = AngularDirection::AUTO

the direction the robot should turn in. AUTO by default

int maxSpeed = 127

the maximum speed the robot can turn at. Value between 0-127. 127 by default

int minSpeed = 0

the minimum speed the robot can turn at. If set to a non-zero value, the `it conditions will switch to less accurate but smoother ones. Value between 0-127. 0 by default

float earlyExitRange = 0

angle between the robot and target point where the movement will exit. Only has an effect if minSpeed is non-zero.

struct TurnToHeadingParams

Parameters for Chassis::turnToHeading.

We use a struct to simplify customization. Chassis::turnToHeading has many parameters and specifying them all just to set one optional param ruins readability. By passing a struct to the function, we can have named parameters, overcoming the c/c++ limitation

Public Members

AngularDirection direction = AngularDirection::AUTO

the direction the robot should turn in. AUTO by default

int maxSpeed = 127

the maximum speed the robot can turn at. Value between 0-127. 127 by default

int minSpeed = 0

the minimum speed the robot can turn at. If set to a non-zero value, the `it conditions will switch to less accurate but smoother ones. Value between 0-127. 0 by default

float earlyExitRange = 0

angle between the robot and target point where the movement will exit. Only has an effect if minSpeed is non-zero.

struct SwingToPointParams

Parameters for Chassis::swingToPoint.

We use a struct to simplify customization. Chassis::swingToPoint has many parameters and specifying them all just to set one optional param harms readability. By passing a struct to the function, we can have named parameters, overcoming the c/c++ limitation

Public Members

bool forwards = true

whether the robot should turn to face the point with the front of the robot. True by default

AngularDirection direction = AngularDirection::AUTO

the direction the robot should turn in. AUTO by default

float maxSpeed = 127

the maximum speed the robot can turn at. Value between 0-127. 127 by default

float minSpeed = 0

the minimum speed the robot can turn at. If set to a non-zero value, the exit conditions will switch to less accurate but smoother ones. Value between 0-127. 0 by default

float earlyExitRange = 0

angle between the robot and target heading where the movement will exit. Only has an effect if minSpeed is non-zero.

struct SwingToHeadingParams

Parameters for Chassis::swingToHeading.

We use a struct to simplify customization. Chassis::swingToHeading has many parameters and specifying them all just to set one optional param harms readability. By passing a struct to the function, we can have named parameters, overcoming the c/c++ limitation

Public Members

AngularDirection direction = AngularDirection::AUTO

the direction the robot should turn in. AUTO by default

float maxSpeed = 127

the maximum speed the robot can turn at. Value between 0-127. 127 by default

float minSpeed = 0

the minimum speed the robot can turn at. If set to a non-zero value, the exit conditions will switch to less accurate but smoother ones. Value between 0-127. 0 by default

float earlyExitRange = 0

angle between the robot and target heading where the movement will exit. Only has an effect if minSpeed is non-zero.

struct MoveToPoseParams

Parameters for Chassis::moveToPose.

We use a struct to simplify customization. Chassis::moveToPose has many parameters and specifying them all just to set one optional param ruins readability. By passing a struct to the function, we can have named parameters, overcoming the c/c++ limitation

Public Members

bool forwards = true

whether the robot should move forwards or backwards. True by default

float horizontalDrift = 0

how fast the robot will move around corners. Recommended value 2-15. 0 means use horizontalDrift set in chassis class. 0 by default.

float lead = 0.6

carrot point multiplier. value between 0 and 1. Higher values result in curvier movements. 0.6 by default

float maxSpeed = 127

the maximum speed the robot can travel at. Value between 0-127. 127 by default

float minSpeed = 0

the minimum speed the robot can travel at. If set to a non-zero value, the exit conditions will switch to less accurate but smoother ones. Value between 0-127. 0 by default

float earlyExitRange = 0

distance between the robot and target point where the movement will exit. Only has an effect if minSpeed is non-zero.

struct MoveToPointParams

Parameters for Chassis::moveToPoint.

We use a struct to simplify customization. Chassis::moveToPoint has many parameters and specifying them all just to set one optional param harms readability. By passing a struct to the function, we can have named parameters, overcoming the c/c++ limitation

Public Members

bool forwards = true

whether the robot should move forwards or backwards. True by default

float maxSpeed = 127

the maximum speed the robot can travel at. Value between 0-127. 127 by default

float minSpeed = 0

the minimum speed the robot can travel at. If set to a non-zero value, the exit conditions will switch to less accurate but smoother ones. Value between 0-127. 0 by default

float earlyExitRange = 0

distance between the robot and target point where the movement will exit. Only has an effect if minSpeed is non-zero.

Builder Classes

class TrackingWheel

Public Functions

TrackingWheel(pros::adi::Encoder *encoder, float wheelDiameter, float distance, float gearRatio = 1)

Create a new tracking wheel.

Example

// Create a new optical shaft encoder on ports 'A' and 'B'
// this sensor is also reversed
pros::adi::Encoder verticalEncoder('A', 'B', true);
// create a new vertical tracking wheel
// it's using a new 2.75 inch wheel
// it's also 5 inches away from the tracking center. This tracking wheel is to the left
// of the tracking center, so we use a negative distance. If it was to the right of the
// tracking center, we would use a positive distance
lemlib::TrackingWheel verticalTrackingWheel(&verticalEncoder, lemlib::Omniwheel::NEW_275, -5);
// create a new optical shaft encoder on ports `C` and `D`
// this sensor is not reversed
pros::adi::Encoder horizontalEncoder('C', 'D', false);
// create a new horizontal tracking wheel
// it's using an old 3.25 inch wheel
// it's also 2 inches away from the tracking center. This tracking wheel is to the back
// of the tracking center, so we use a negative distance. If it was to the front of the
// tracking center, we would use a positive distance
// this wheel also has a 5:3 gear ratio
lemlib::TrackingWheel horizontalTrackingWheel(&horizontalEncoder, lemlib::Omniwheel::OLD_325, -2, 5.0/3.0);

Parameters:
  • encoder – the optical shaft encoder to use

  • wheelDiameter – the diameter of the wheel

  • distance – distance between the tracking wheel and the center of rotation in inches

  • gearRatio – gear ratio of the tracking wheel, defaults to 1

TrackingWheel(pros::Rotation *encoder, float wheelDiameter, float distance, float gearRatio = 1)

Create a new tracking wheel.

Example

// Create a new rotation sensor on port 1
// this sensor is not reversed
pros::Rotation verticalEncoder(1, false);
// create a new vertical tracking wheel
// it's using a new 2.75 inch wheel
// it's also 5 inches away from the tracking center. This tracking wheel is to the left
// of the tracking center, so we use a negative distance. If it was to the right of the
// tracking center, we would use a positive distance
lemlib::TrackingWheel verticalTrackingWheel(&verticalEncoder, lemlib::Omniwheel::NEW_275, -5);
// create a new rotation sensor on port 2
// this sensor is reversed
pros::Rotation horizontalEncoder(2, true);
// create a new horizontal tracking wheel
// it's using an old 3.25 inch wheel
// it's also 2 inches away from the tracking center. This tracking wheel is to the back
// of the tracking center, so we use a negative distance. If it was to the front of the
// tracking center, we would use a positive distance
// this wheel also has a 5:3 gear ratio
lemlib::TrackingWheel horizontalTrackingWheel(&horizontalEncoder, lemlib::Omniwheel::OLD_325, -2, 5.0/3.0);

Parameters:
  • encoder – the v5 rotation sensor to use

  • wheelDiameter – the diameter of the wheel

  • distance – distance between the tracking wheel and the center of rotation in inches

  • gearRatio – gear ratio of the tracking wheel, defaults to 1

TrackingWheel(pros::MotorGroup *motors, float wheelDiameter, float distance, float rpm)

Create a new tracking wheel.

Example

// Create motor objects
// note its important to include the motor gearset otherwise the gear ratio will be incorrect
pros::Motor lF(-5, pros::E_MOTOR_GEARSET_06); // left front motor. port 5, reversed
pros::Motor lM(4, pros::E_MOTOR_GEARSET_06); // left middle motor. port 4
pros::Motor lB(-3, pros::E_MOTOR_GEARSET_06); // left back motor. port 3, reversed
// create a motor group for the left side of the drivetrain
pros::MotorGroup leftMotors({lF, lM, lB});
// Create a new tracking wheel using the left motor group
// it's using an old 4 inch wheel
// and its distance is half the track width of the drivetrain
// distance is also negative because the left drive side is to the left of the tracking center
// if it was to the right of the tracking center, we would use a positive distance
// the rpm is 360
lemlib::TrackingWheel leftTrackingWheel(&leftMotors, lemlib::Omniwheel::OLD_4, -5, 360);

Parameters:
  • motors – the motor group to use

  • wheelDiameter – the diameter of the wheel

  • distance – half the track width of the drivetrain in inches

  • rpm – theoretical maximum rpm of the drivetrain wheels

void reset()

Reset the tracking wheel position to 0.

If you are using odometry provided by LemLib, this will automatically be called when the chassis is calibrated

Example

void initialize() {
    exampleTrackingWheel.reset();
    // this will now return 0 inches traveled
    exampleTrackingWheel.getDistanceTraveled();
}

float getOffset()

Get the distance traveled by the tracking wheel.

Example

   void initialize() {
       while (true) {
           // print the distance traveled by the tracking wheel to the terminal
           std::cout << "distance: " << exampleTrackingWheel.getDistanceTraveled() << std::endl;
           pros::delay(10);
       }
   }
  /
float getDistanceTraveled();

Returns:

float distance traveled in inches

int getType()

Get the type of tracking wheel.

Example

void initialize() {
    // create a tracking wheel that uses a rotation sensor
    lemlib::TrackingWheel exampleTrackingWheel(&exampleRotationSensor, lemlib::Omniwheel::NEW_275, 0.5);
    // this prints 0 to the terminal, because it uses a rotation sensor. If it used a motor group, it would
    // have returned 1
    std::cout << "type: " << exampleTrackingWheel.getType() << std::endl;
}

Returns:

int - 1 if motor group, 0 otherwise

class OdomSensors

class containing the sensors used for odometry

Public Functions

OdomSensors(TrackingWheel *vertical1, TrackingWheel *vertical2, TrackingWheel *horizontal1, TrackingWheel *horizontal2, pros::Imu *imu)

The sensors are stored in a class so that they can be easily passed to the chassis class The variables are pointers so that they can be set to nullptr if they are not used Otherwise the chassis class would have to have a constructor for each possible combination of sensors

Example

pros::Rotation vertical_rotation(1); // rotation sensor on port 1
pros::Imu imu(2); // IMU on port 2
// tracking wheel using a new 2.75" wheel, 0.5 inches to the right of the tracking center
lemlib::TrackingWheel vertical1(&vertical_rotation, lemlib::Omniwheel::NEW_275, 0.5);
lemlib::OdomSensors sensors(&vertical1, // vertical tracking wheel
                    nullptr, // no second vertical tracking wheel, set to nullptr
                    nullptr, // no horizontal tracking wheels, set to nullptr
                    nullptr, // no second horizontal tracking wheel, set to nullptr
                    &imu); // IMU

Parameters:
  • vertical1 – pointer to the first vertical tracking wheel

  • vertical2 – pointer to the second vertical tracking wheel

  • horizontal1 – pointer to the first horizontal tracking wheel

  • horizontal2 – pointer to the second horizontal tracking wheel

  • imu – pointer to the IMU

namespace Omniwheel

A namespace representing the size of omniwheels.

Variables

constexpr float NEW_2 = 2.125
constexpr float NEW_275 = 2.75
constexpr float OLD_275 = 2.75
constexpr float NEW_275_HALF = 2.744
constexpr float OLD_275_HALF = 2.74
constexpr float NEW_325 = 3.25
constexpr float OLD_325 = 3.25
constexpr float NEW_325_HALF = 3.246
constexpr float OLD_325_HALF = 3.246
constexpr float NEW_4 = 4
constexpr float OLD_4 = 4.18
constexpr float NEW_4_HALF = 3.995
constexpr float OLD_4_HALF = 4.175
class Drivetrain

class containing constants for a drivetrain

Public Functions

Drivetrain(pros::MotorGroup *leftMotors, pros::MotorGroup *rightMotors, float trackWidth, float wheelDiameter, float rpm, float horizontalDrift)

Drivetrain constructor.

The constants are stored in a class so that they can be easily passed to the chassis class Set a constant to 0 and it will be ignored

Example

// drive motors
pros::Motor lF(-5, pros::E_MOTOR_GEARSET_06); // left front motor. port 5, reversed
pros::Motor lM(4, pros::E_MOTOR_GEARSET_06); // left middle motor. port 4
pros::Motor lB(-3, pros::E_MOTOR_GEARSET_06); // left back motor. port 3, reversed
pros::Motor rF(6, pros::E_MOTOR_GEARSET_06); // right front motor. port 6
pros::Motor rM(-9, pros::E_MOTOR_GEARSET_06); // right middle motor. port 9, reversed
pros::Motor rB(7, pros::E_MOTOR_GEARSET_06); // right back motor. port 7

// motor groups
pros::MotorGroup leftMotors({lF, lM, lB}); // left motor group
pros::MotorGroup rightMotors({rF, rM, rB}); // right motor group

lemlib::Drivetrain drivetrain(&leftMotors, // left motor group
                              &rightMotors, // right motor group
                              10, // 10 inch track width
                              lemlib::Omniwheel::NEW_4, // using new 4" omnis
                              360, // drivetrain rpm is 360
                              2); // horizontalDrift is 2. If we had traction wheels, it would have been 8

Parameters:
  • leftMotors – pointer to the left motors

  • rightMotors – pointer to the right motors

  • trackWidth – the track width of the robot, in inches. This is the distance from the left wheels to the right wheels

  • wheelDiameter – the diameter of the wheel used on the drivetrain, in inches

  • rpm – the rpm of the wheels

  • horizontalDrift – higher values make the robot move faster but causes more overshoot on turns. Recommended value of 2 if not using traction wheels, 8 if using traction wheels

class ControllerSettings

class containing constants for a chassis controller

Public Functions

inline ControllerSettings(float kP, float kI, float kD, float windupRange, float smallError, float smallErrorTimeout, float largeError, float largeErrorTimeout, float slew)

ControllerSettings constructor.

The constants are stored in a class so that they can be easily passed to the chassis class Set a constant to 0 and it will be ignored

Example

lemlib::ControllerSettings lateralSettings(10, // proportional gain (kP)
                                           0, // integral gain (kI), set to 0 to disable
                                           3, // derivative gain (kD), set to 3
                                           3, // integral anti windup range, set to 0 to disable
                                           1, // small error range, in inches
                                           100, // small error range timeout, in milliseconds
                                           3, // large error range, in inches
                                           500, // large error range timeout, in milliseconds
                                           5); // maximum acceleration (slew)

Parameters:
  • kP – proportional gain

  • kI – integral gain

  • kD – derivative gain

  • antiWindup – integral anti windup range. If error is within this range, integral is set to 0

  • smallError – range of error at which the chassis controller will exit if the error is within this range for an amount of time determined by smallErrorTimeout

  • smallErrorTimeout – the time the chassis controller will wait before exiting if error is within a certain range determined by smallError

  • largeError – range of error at which the chassis controller will exit if the error is within this range for an amount of time determined by largeErrorTimeout

  • largeErrorTimeout – the time the chassis controller will wait before exiting if error is within a certain range determined by largeError

  • slew – maximum acceleration

class ExitCondition

Public Functions

ExitCondition(const float range, const int time)

Create a new Exit Condition.

Example

// create a new exit condition that will exit if the input is within 0.1 of the target for 1000ms
ExitCondition ec(0.1, 1000);

Parameters:
  • range – the range where the countdown is allowed to start

  • time – how much time to wait while in range before exiting

bool getExit()

whether the exit condition has been met

Example

// check if the exit condition has been met
if (ec.getExit()) {
    // do something
}

Returns:

true exit condition met

Returns:

false exit condition not met

bool update(const float input)

update the exit condition

Example

// update the exit condition
// this is typically called in a loop
while (!ec.getExit()) {
    // do something
    ec.update(input);
}

Parameters:

input – the input for the exit condition

Returns:

true exit condition met

Returns:

false exit condition not met

void reset()

reset the exit condition timer

Example

// reset the exit condition timer
ec.reset();

class DriveCurve

abstract DriveCurve class

This is an abstract class to enable users to provide their own, custom drive curves for LemLib to use.

Subclassed by lemlib::ExpoDriveCurve

Public Functions

virtual float curve(float input) = 0

Processes an input and returns an output.

This is a pure virtual function that needs to be overriden by child classes

Parameters:

input – the input to process

Returns:

float output

class ExpoDriveCurve : public lemlib::DriveCurve

ExpoDriveCurve class. Inherits from the DriveCurve class. This is a exponential drive curve.

see https://www.desmos.com/calculator/umicbymbnl for an interactive graph see https://www.vexforum.com/t/expo-drive-lemlibs-implementation for a detailed explanation

Public Functions

ExpoDriveCurve(float deadband, float minOutput, float curve)

Construct a new Expo Drive Curve object.

see https://www.desmos.com/calculator/umicbymbnl for an interactive graph see https://www.vexforum.com/t/expo-drive-lemlibs-implementation for a detailed explanation

Example

// create a new exponential drive curve
// controller deadband is set to 5
// minimum output is set to 12
// curve gain is set to 1.132
lemlib::ExpoDriveCurve driveCurve(5, 12, 1.132);

Parameters:
  • deadband – range where input is considered to be input

  • minOutput – the minimum output that can be returned

  • curve – how “curved” the graph is

virtual float curve(float input)

curve an input

Example

void opcontrol() {
    // create a new exponential drive curve
    lemlib::ExpoDriveCurve driveCurve(5, 12, 1.132);
    // input 4
    std::cout << driveCurve.curve(4) << std::endl; // outputs 0 because input is within deadzone
    //  input 6
    std::cout << driveCurve.curve(6) << std::endl; // outputs 12, the minimum output
    std::cout << driveCurve.curve(127) << std::endl; // outputs 127, the maximum output
}

Parameters:

input – the input to curve

Returns:

float the curved output