-
Notifications
You must be signed in to change notification settings - Fork 0
Examples
Important
Be sure you have a RobotConfig set up! You may read this page to learn how to make such a file.
The most vital component of a BunyipsLib OpMode is the abstract OpMode variant that is chosen. Various OpMode abstractions exist for different purposes, but all pool towards the same ideas. Instead of extending a LinearOpMode, you choose from a variant that suits your application the best. Below is a table of the three OpModes bases used in competition.
OpMode variant | Extends | Purpose | Use cases |
---|---|---|---|
BunyipsOpMode | LinearOpMode | All-use utility-driven OpMode | Any, primarily procedural TeleOp |
AutonomousBunyipsOpMode | BunyipsOpMode | Autonomous with a built-in task queue system | Autonomous OpModes |
CommandBasedBunyipsOpMode | BunyipsOpMode | Integrated with the Scheduler , allows built-in command-based paradigms |
TeleOp w/ commands |
There also exists some utility abstract OpModes that can be used but are not designed for competition.
OpMode variant | Extends | Purpose | Use cases |
---|---|---|---|
ColourTunerOpMode | BunyipsOpMode | Live dashboard tuning of ColourThreshold vision processors |
Debugging colour thresholds using a gamepad |
RoadRunnerTuningOpMode | LinearOpMode | Uses a telemetry menu to select from the various RoadRunner 0.5 tuning OpModes | RoadRunner tuning from one OpMode only |
PathRecorderOpMode | BunyipsOpMode | Records RoadRunner poses over time to make a continuous spline | Differential drive gamepad-to-spline pathing |
There are a few different ways of creating a TeleOp with BunyipsLib, primarily Iterative and Command-based TeleOp.
Below is a basic teleop that doesn't use command-based functions. It also assumes you aren't using RoadRunner for your drive. It is recommended to use RoadRunner, which you may read about in the RoadRunner section.
import org.murraybridgebunyips.bunyipslib.BunyipsOpMode;
import org.murraybridgebunyips.bunyipslib.drive.CartesianMecanumDrive;
import org.murraybridgebunyips.bunyipslib.subsystems.DualServos;
import org.murraybridgebunyips.bunyipslib.subsystems.HoldableActuator;
/**
* A basic TeleOp that doesn't use command-based functions.
* This is modelled after a basic robot with a Mecanum drive, arm, and two claws (appropriate season of CENTERSTAGE)
*/
@TeleOp
public class BasicTeleOp extends BunyipsOpMode {
private final ExampleConfig config = new ExampleConfig();
// All subsystems must be instantiated during onInit(), otherwise hardware will be null and the DS will not be happy with you
private CartesianMecanumDrive drive;
private HoldableActuator arm;
private DualServos claws;
@Override
protected void onInit() {
// Required to be called to assign your hardware from your config. This will run onRuntime().
config.init();
// For this example, we use CartesianMecanumDrive, however, if you are using a RoadRunner drive (recommended), use the MecanumDrive class.
// CartesianMecanumDrive simply runs the Mecanum calculations for a set of four wheels, and is useful for simple implementations. Note
// the pose system for CartesianMecanumDrive is based off Cartesian traversal (y axis forward, see more in the RoadRunner section)
drive = new CartesianMecanumDrive(config.front_left, config.front_right, config.back_left, config.back_right);
// HoldableActuator is a generic motor-powered component that will hold its position with an encoder when no power is supplied.
arm = new HoldableActuator(config.arm);
// Generic dual servo controller subsystem that takes in setpoints for open and closed (0,1 here)
claws = new DualServos(config.left_claw, config.right_claw, 0.0, 1.0, 0.0, 1.0);
}
@Override
protected void activeLoop() {
// Convenience method attached to Mecanum Drivetrains to have the left stick control translation and the right stick control rotation
// Note BunyipsLib provides alias for gamepad properties left_stick_x->lsx left_stick_y->lsy and right_stick_x->rsx for convenience
drive.setSpeedUsingController(gamepad1.lsx, gamepad1.lsy, gamepad1.rsx);
// These methods are exposed as per the generic HoldableActuator subsystem
arm.setPower(-gamepad2.lsy); // Sets the arm to be controlled with the second gamepad's left stick, reversed.
// getDebounced custom method on controllers removes the need to create your own rising-edge detection with booleans
// This method will do rising edge detection on a selected button, in this case gamepad2.x and gamepad2.b
if (gamepad2.getDebounced(Controls.X)) {
claws.toggle(DualServos.ServoSide.LEFT);
} else if (gamepad2.getDebounced(Controls.B)) {
claws.toggle(DualServos.ServoSide.RIGHT);
}
// These send stateful updates to the hardware and are required when working with subsystems yourself.
drive.update();
arm.update();
claws.update();
}
}
Subsystems and tasks/commands are a paradigm of BunyipsLib graciously borrowed from FRC. You may read more about how this paradigm is used in BunyipsLib here. It is wise to familiarise yourself with the paradigm before using it, as it is powerful but needs you to think differently about robot operation. You have already used subsystems in the previous example, but the command-based implementation expands this to an entire paradigm.
Below is a TeleOp using these systems, assuming you are not using RoadRunner for your drive. Note that we extend CommandBasedBunyipsOpMode
, and update cycles are managed by an external Scheduler
. The intrinsics of these paradigms and OpMode variants are explained separately in their appropriate wiki section.
import org.murraybridgebunyips.bunyipslib.CommandBasedBunyipsOpMode;
import org.murraybridgebunyips.bunyipslib.Controller;
import org.murraybridgebunyips.bunyipslib.Controls;
import org.murraybridgebunyips.bunyipslib.drive.CartesianMecanumDrive;
import org.murraybridgebunyips.bunyipslib.subsystems.DualServos;
import org.murraybridgebunyips.bunyipslib.subsystems.HoldableActuator;
/**
* Basic Command-Based TeleOp.
*/
public class CommandBasedTeleOp extends CommandBasedBunyipsOpMode {
private final ExampleConfig config = new ExampleConfig();
private CartesianMecanumDrive drive;
private HoldableActuator arm;
private DualServos claws;
@Override
protected void onInitialise() {
config.init();
// Similar instantiation of subsystems from the iterative approach
drive = new CartesianMecanumDrive(config.front_left, config.front_right, config.back_left, config.back_right);
arm = new HoldableActuator(config.arm);
claws = new DualServos(config.left_claw, config.right_claw, 0.0, 1.0, 0.0, 1.0);
}
@Override
protected void assignCommands() {
// Command-Based OpModes uses tasks. Most functions, unless they're explicitly tasks, have task and non-task variants,
// allowing for use in both kinds of TeleOp. Tasks are accessed through the `tasks` field, which is available on all common subsystems.
// Subsystem conventions are to be explained in another section.
operator().whenPressed(Controls.X)
.run(claws.tasks.toggleLeft());
operator().whenPressed(Controls.B)
.run(claws.toggleTask(DualServos.ServoSide.RIGHT));
// Defines default tasks that will run on the appropriate subsystem when no other task needs to run on this subsystem
// These paradigms are explained further in the command-based section.
arm.setDefaultTask(linearActuator.tasks.control(() -> -gamepad2.lsy));
drive.setDefaultTask(new HolonomicDriveTask(gamepad1, drive, () -> false));
}
// periodic() is similar to the activeLoop(), allowing you to integrate any other constant loop code as well without being limited
// by the abstraction of CommandBasedBunyipsOpMode.
@Override
protected void periodic() {
// Uses .big() for HTML formatting. All telemetry objects made through .add() return a HtmlItem.
telemetry.add("Left Claw: " + (claws.isOpen(DualServos.ServoSide.LEFT) ? "Open" : "Closed")).big();
telemetry.add("Right Claw: " + (claws.isOpen(DualServos.ServoSide.RIGHT) ? "Open" : "Closed")).big();
}
}