Using and Creating a Drivetrain
A Drivetrain is an Attachment that houses your Robot’s drive logic.
Volt currently provides one pre-built Drivetrain type: MecanumDrivetrain.
MecanumDrivetrain
Section titled “MecanumDrivetrain”MecanumDrivetrain is an abstract Drivetrain class for four wheel mecanum drive robots. It has one method: setDrivePowers.
setDrivePowers takes a PoseVelocity2d that can be used to power each motor.
Implementations of MecanumDrivetrain are designed to work with RobotWithMecanumDrivetrain.
There are two pre-built implementations of MecanumDrivetrain:
MecanumDriveWithRR: AMecanumDrivetrainimplementation using RoadRunnerMecanumDriveWithPP: AMecanumDrivetrainimplementation using PedroPathing
Using MecanumDriveWithRR
Section titled “Using MecanumDriveWithRR”MecanumDriveWithRR constructor parameters:
hardwareMap: HardwareMap: Used to get drive motorspose: Pose2d: Used to set the Robot’s initial poseparams: MecanumDriveWithRR.DriveParams: Used to configure RoadRunner
trajectory Builder
Section titled “trajectory Builder”MecanumDriveWithRR provides a trajectory builder that composes Actions using RoadRunner’s TrajectoryActionBuilder.
Example
Section titled “Example”class ExampleRobot( hardwareMap: HardwareMap) : RobotWithMecanumDrivetrain<MecanumDriveWithRR>( hardwareMap, MecanumDriveWithRR(hardwareMap)) { fun driveForwardAction() = drivetrain.trajectory { strafeTo(Vector2d(24.0, 0.0)) }}public class ExampleRobot extends RobotWithMecanumDrivetrain<MecanumDriveWithRR> { public ExampleRobot(HardwareMap hardwareMap) { super(hardwareMap, new MecanumDriveWithRR(hardwareMap)); }
public Action driveForwardAction() { return drivetrain.trajectory(builder -> { builder.strafeTo(new Vector2d(24.0, 0.0)); return Unit.INSTANCE; }); }}Using MecanumDriveWithPP
Section titled “Using MecanumDriveWithPP”MecanumDriveWithPP constructor parameters:
hardwareMap: HardwareMap: Used to get drive motorsfollowerConstants: FollowerConstants: Used to configure PedroPathing’s path followerlocalizerConstants: DriveEncoderConstants: Used to configure PedroPathing’s drive encoder localizerpathConstraints: PathConstraints: Used to configure PedroPathing’s path following constraintsdriveConstants: MecanumConstants: Used to configure PedroPathing’s mecanum drivetrain logicinitialPose: Pose: Used to set the Robot’s initial pose
path Builder
Section titled “path Builder”MecanumDriveWithPP provides a path builder that composes Actions using a custom FollowerActionBuilder (built on PedroPathing’s path builder).
Example
Section titled “Example”class ExampleRobot( hardwareMap: HardwareMap) : RobotWithMecanumDrivetrain<MecanumDriveWithPP>( hardwareMap, MecanumDriveWithPP( hardwareMap, FollowerConstants(), DriveEncoderConstants(), PathConstraints(), MecanumConstants() )) { fun driveAction() = drivetrain.path { lineTo(Pose(24.0, 0.0, 0.0)) }}public class ExampleRobot extends RobotWithMecanumDrivetrain<MecanumDriveWithPP> { public ExampleRobot(HardwareMap hardwareMap) { super(hardwareMap, new MecanumDriveWithPP( hardwareMap, FollowerConstants(), DriveEncoderConstants(), PathConstraints(), MecanumConstants() )); }
public Action driveAction() { return drivetrain.path(builder -> { builder.lineTo(new Pose(24.0, 0.0, 0.0)); return Unit.INSTANCE; }); }}Creating a Custom Drivetrain
Section titled “Creating a Custom Drivetrain”Building a custom Drivetrain class is just like building an Attachment:
- Extend
Drivetrain(orMecanumDrivetrain) - Configure hardware
- Write drive logic
Basic Example
Section titled “Basic Example”class ExampleDrivetrain(hardwareMap: HardwareMap) : Drivetrain() { val leftFront: DcMotorEx = hardwareMap.get(DcMotorEx::class.java, "lf") val leftBack: DcMotorEx = hardwareMap.get(DcMotorEx::class.java, "lr") val rightBack: DcMotorEx = hardwareMap.get(DcMotorEx::class.java, "rr") val rightFront: DcMotorEx = hardwareMap.get(DcMotorEx::class.java, "rf")
// Define drive actions here}public class ExampleDrivetrain extends Drivetrain { public DcMotorEx leftFront; public DcMotorEx leftBack; public DcMotorEx rightBack; public DcMotorEx rightFront;
public ExampleDrivetrain(HardwareMap hardwareMap) { super(); leftFront = hardwareMap.get(DcMotorEx.class, "lf"); leftBack = hardwareMap.get(DcMotorEx.class, "lr"); rightBack = hardwareMap.get(DcMotorEx.class, "rr"); rightFront = hardwareMap.get(DcMotorEx.class, "rf"); }
// Define drive actions here}Next Steps
Section titled “Next Steps”- Create an OpMode that controls your drivetrain
- Learn more about Actions