RobotConfig
Configure your robot's motors, localization, and control parameters
Overview
The RobotConfig class is the central configuration hub for your robot. It defines motor names, directions, localization settings, PID coefficients, and path constraints. Everything in one place!
Drivetrain
Motor configuration & directions
Localization
Position tracking system
PID Control
Tuning coefficients
Constraints
Speed & acceleration limits
Complete Example
Here's a complete RobotConfig class with all necessary configurations:
package org.firstinspires.ftc.teamcode;
import com.vingvingrobot.control.PIDFCoefficients;
import com.vingvingrobot.control.FilteredPIDFCoefficients;
import com.vingvingrobot.follower.Follower;
import com.vingvingrobot.follower.FollowerConstants;
import com.vingvingrobot.ftc.FollowerBuilder;
import com.vingvingrobot.ftc.drivetrains.MecanumConstants;
import com.vingvingrobot.ftc.localization.constants.PinpointConstants;
import com.vingvingrobot.paths.PathConstraints;
import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
public class RobotConfig {
// Drivetrain Configuration
public static MecanumConstants driveConstants = new MecanumConstants()
.maxPower(1.0)
// Motor Names (match your hardware configuration)
.rightFrontMotorName("rightFront")
.rightRearMotorName("rightRear")
.leftRearMotorName("leftRear")
.leftFrontMotorName("leftFront")
// Motor Directions (adjust based on your robot)
.leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE)
.leftRearMotorDirection(DcMotorSimple.Direction.REVERSE)
.rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD)
.rightRearMotorDirection(DcMotorSimple.Direction.FORWARD)
// Velocity (inches per second at full power)
// Use automatic tuner to find these values!
.xVelocity(50.0) // Forward velocity
.yVelocity(48.0); // Strafe velocity
// Localization Configuration (using GoBilda Pinpoint)
public static PinpointConstants localizerConstants = new PinpointConstants()
.forwardPodY(0) // Y offset of forward pod (in inches)
.strafePodX(0) // X offset of strafe pod (in inches)
.distanceUnit(DistanceUnit.INCH)
.hardwareMapName("pinpoint")
.encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)
.forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD)
.strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED);
// Follower Configuration
public static FollowerConstants followerConstants = new FollowerConstants()
.mass(10.0) // Robot mass in kg
// Zero-power acceleration (negative = deceleration)
// Use automatic tuner to find these values!
.forwardZeroPowerAcceleration(-40.0)
.lateralZeroPowerAcceleration(-40.0)
// Translational PID - Controls position error
.translationalPIDFCoefficients(new PIDFCoefficients(
0.1, // P - Proportional gain
0.0, // I - Integral gain
0.01, // D - Derivative gain
0.003 // F - Feedforward gain
))
// Heading PID - Controls rotation error
.headingPIDFCoefficients(new PIDFCoefficients(
1.0, // P
0.0, // I
0.0, // D
0.005 // F
))
// Drive PID - Controls forward/backward movement
.drivePIDFCoefficients(new FilteredPIDFCoefficients(
0.5, // P
0.001, // I
0.001, // D
0.6, // F
0.75 // Filter coefficient
))
// Centripetal scaling for curved paths
.centripetalScaling(0.0005);
// Path Constraints
public static PathConstraints pathConstraints = new PathConstraints(
0.99, // Max power (0.0 to 1.0)
100.0, // Max velocity (inches/second)
1.0, // Max acceleration (inches/second²)
1.0 // Max deceleration (inches/second²)
);
// Create Follower Instance
public static Follower createFollower(HardwareMap hardwareMap) {
return new FollowerBuilder(followerConstants, hardwareMap)
.pathConstraints(pathConstraints)
.mecanumDrivetrain(driveConstants)
.pinpointLocalizer(localizerConstants)
.build();
}
}Configuration Breakdown
Drivetrain Configuration
Motor Names
Motor names must exactly match those in your robot's hardware configuration.
.rightFrontMotorName("rightFront")
.rightRearMotorName("rightRear")
.leftRearMotorName("leftRear")
.leftFrontMotorName("leftFront")Motor Directions
Set motor directions so that positive power moves the robot forward. Test each motor individually to determine the correct direction.
.leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE)
.leftRearMotorDirection(DcMotorSimple.Direction.REVERSE)
.rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD)
.rightRearMotorDirection(DcMotorSimple.Direction.FORWARD)Velocity Values
Maximum velocity in inches per second at full power. Use the Automatic Tuner to measure these accurately!
.xVelocity(50.0) // Forward velocity (in/s)
.yVelocity(48.0) // Strafe velocity (in/s)Localization Configuration
VingVing Robot supports multiple localization systems. Choose the one that matches your hardware:
GoBilda Pinpoint▼
public static PinpointConstants localizerConstants =
new PinpointConstants()
.forwardPodY(0)
.strafePodX(0)
.distanceUnit(DistanceUnit.INCH)
.hardwareMapName("pinpoint")
.encoderResolution(
GoBildaPinpointDriver.GoBildaOdometryPods
.goBILDA_4_BAR_POD
)
.forwardEncoderDirection(
GoBildaPinpointDriver.EncoderDirection.FORWARD
)
.strafeEncoderDirection(
GoBildaPinpointDriver.EncoderDirection.REVERSED
);
// In createFollower():
.pinpointLocalizer(localizerConstants)Three Wheel Odometry▼
public static ThreeWheelConstants localizerConstants =
new ThreeWheelConstants()
.leftEncoderName("leftEncoder")
.rightEncoderName("rightEncoder")
.strafeEncoderName("strafeEncoder")
.leftEncoderDirection(Encoder.FORWARD)
.rightEncoderDirection(Encoder.REVERSE)
.strafeEncoderDirection(Encoder.FORWARD)
.leftYOffset(6.0)
.rightYOffset(6.0)
.strafeXOffset(0.0)
.ticksPerInch(2000.0 / (Math.PI * 1.5));
// In createFollower():
.threeWheelLocalizer(localizerConstants)Two Wheel + IMU▼
public static TwoWheelConstants localizerConstants =
new TwoWheelConstants()
.forwardEncoderName("forwardEncoder")
.strafeEncoderName("strafeEncoder")
.forwardEncoderDirection(Encoder.FORWARD)
.strafeEncoderDirection(Encoder.FORWARD)
.forwardYOffset(0.0)
.strafeXOffset(0.0)
.ticksPerInch(2000.0 / (Math.PI * 1.5))
.imuName("imu");
// In createFollower():
.twoWheelLocalizer(localizerConstants)SparkFun OTOS▼
public static OTOSConstants localizerConstants =
new OTOSConstants()
.hardwareMapName("sensor_otos")
.offset(new Pose(0, 0, 0))
.linearScalar(1.0)
.angularScalar(1.0)
.distanceUnit(DistanceUnit.INCH);
// In createFollower():
.otosLocalizer(localizerConstants)PID Control Configuration
VingVing Robot uses four PID controllers for precise movement control. Start with the default values shown above, then use the tuning tools to optimize them for your robot.
Translational PID
Controls the robot's lateral (sideways) movement and position error correction
P: 0.1, I: 0.0, D: 0.01, F: 0.003Heading PID
Controls the robot's rotation and heading error correction
P: 1.0, I: 0.0, D: 0.0, F: 0.005Drive PID
Controls forward/backward movement along the path
P: 0.5, I: 0.001, D: 0.001, F: 0.6Centripetal Scaling
Compensates for centripetal force during curved paths
Scaling: 0.0005Path Constraints
Path constraints limit the robot's speed and acceleration for safety and control.
public static PathConstraints pathConstraints = new PathConstraints(
0.99, // Max power (0.0 to 1.0)
100.0, // Max velocity (inches/second)
1.0, // Max acceleration (inches/second²)
1.0 // Max deceleration (inches/second²)
);Maximum motor power (0.0 - 1.0). Lower for more control, higher for speed.
Maximum robot speed in inches per second along the path.
How quickly the robot can speed up.
How quickly the robot can slow down.
Using RobotConfig in OpModes
Once configured, creating a Follower instance in your OpMode is simple:
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.vingvingrobot.follower.Follower;
import com.vingvingrobot.geometry.Pose;
import com.vingvingrobot.paths.Path;
import com.vingvingrobot.geometry.BezierLine;
@Autonomous(name = "My Autonomous")
public class MyAutonomous extends LinearOpMode {
private Follower follower;
@Override
public void runOpMode() {
// Create follower from RobotConfig
follower = RobotConfig.createFollower(hardwareMap);
// Set starting position
follower.setStartingPose(new Pose(0, 0, 0));
waitForStart();
// Create and follow a path
Path myPath = new Path(new BezierLine(
new Pose(0, 0, 0),
new Pose(24, 24, Math.toRadians(90))
));
follower.followPath(myPath);
while (opModeIsActive() && follower.isBusy()) {
follower.update();
telemetry.addData("X", follower.getPose().getX());
telemetry.addData("Y", follower.getPose().getY());
telemetry.addData("Heading", Math.toDegrees(follower.getPose().getHeading()));
telemetry.update();
}
}
}Next Steps
Now that your robot is configured, it's time to tune the parameters!