Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
8d24305
:(
athGurnani Jan 28, 2026
13eb5d1
Fixing Tuners for Pedro
chetanvanam Jan 29, 2026
2f0490d
Add Kotlin
athGurnani Jan 31, 2026
ef4a49b
fix
athGurnani Feb 2, 2026
184b7a3
Refactor start method in BlueFar.java
athGurnani Feb 5, 2026
b3aec0a
SORT:)
athGurnani Feb 6, 2026
f2adb1f
config?
athGurnani Feb 6, 2026
983f394
Add Kotlin
athGurnani Feb 7, 2026
61d83f4
Merge branch 'Korver-League-Tournament' of github.com:Bionic-Dutch-Ro…
athGurnani Feb 7, 2026
dfdcbd4
add sort
athGurnani Feb 7, 2026
dbe23eb
Make Bindings removable from a Controller
athGurnani Feb 10, 2026
cbe5e25
Create a test for local Pedro Heading Lock and practice Kotlin
athGurnani Feb 10, 2026
ab51573
Fix null pointer in KotlinTest
athGurnani Feb 10, 2026
747f1f5
Make PedroPathing version local
athGurnani Feb 10, 2026
711db05
Remove korver_state and copy korver_v3 config (didn't work)
athGurnani Feb 10, 2026
40ba72c
Merge remote-tracking branch 'origin/Korver-League-Tournament' into K…
chetanvanam Feb 10, 2026
75653f1
Finally finished Pedro Tuning :)
chetanvanam Feb 11, 2026
1e2e7c4
Remove heading lock (temporary)
athGurnani Feb 11, 2026
03cde86
Expand on command-based system
athGurnani Feb 11, 2026
4b1a759
remove local Pedro
athGurnani Feb 11, 2026
9f8625e
Remove unnecessary lines
athGurnani Feb 11, 2026
e3fdb9d
Merge branch 'Korver-League-Tournament' of https://github.com/Bionic-…
athGurnani Feb 11, 2026
82690e9
Create AugmentedOpMode for easier Controller/Command usage as well as…
athGurnani Feb 12, 2026
ea16c12
Add Controller settings and LynxHub subsystem
athGurnani Feb 12, 2026
620ba30
shooter prediction + auto
athGurnani Feb 13, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 23 additions & 0 deletions TeamCode/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ apply from: '../build.common.gradle'
apply from: '../build.dependencies.gradle'
apply plugin: "org.team11260.fast-load-plugin"
apply plugin: 'dev.frozenmilk.sinister.sloth.load'
apply plugin: 'org.jetbrains.kotlin.android'


android {
Expand All @@ -47,6 +48,9 @@ android {
}
jniLibs.useLegacyPackaging true
}
kotlinOptions {
jvmTarget = '1.8'
}
}

repositories {
Expand All @@ -56,6 +60,25 @@ repositories {
maven {
url = "https://www.methewo.tech/maven/"
}
maven {
url = 'https://jitpack.io'
}
}

android {
namespace = 'org.firstinspires.ftc.teamcode'

kotlinOptions {
jvmTarget='1.8'
}
compileSdk 34
defaultConfig {
minSdk 24
}

packagingOptions {
jniLibs.useLegacyPackaging true
}
}

dependencies {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
package org.firstinspires.ftc.teamcode.autos;

import static org.firstinspires.ftc.teamcode.util.Hardware.dt;
import static org.firstinspires.ftc.teamcode.util.Hardware.intake;
import static org.firstinspires.ftc.teamcode.util.Hardware.shooter;
import static org.firstinspires.ftc.teamcode.util.Hardware.transfer;

import com.pedropathing.geometry.BezierCurve;
import com.pedropathing.geometry.BezierLine;
import com.pedropathing.geometry.Pose;
Expand All @@ -9,35 +14,48 @@

import org.firstinspires.ftc.teamcode.subsystems.drivetrain.Drivetrain;
import org.firstinspires.ftc.teamcode.util.AllianceColor;
import org.firstinspires.ftc.teamcode.util.MatchSettings;

@Autonomous(name="Drivetrain Only")
public class DrivetrainOnlyAuto extends OpMode {
private Path path;
private Drivetrain dt;
private AutoState state;

@Override
public void init() {
dt = new Drivetrain(hardwareMap, new AllianceColor(AllianceColor.Selection.BLUE), new Pose(-gamepad1.left_stick_x, -gamepad1.left_stick_y, -gamepad1.right_stick_x), new Pose(1.15, 1.15, 1.15));
MatchSettings.initSelection(hardwareMap, new AllianceColor(AllianceColor.Selection.BLUE), gamepad1);
MatchSettings.start();
}

@Override
public void start() {
path = new Path(
new BezierCurve(
dt.follower.getPose(),
new Pose(75, 35),
new Pose(45, 32),
new Pose(25,30,dt.follower.getPose().getHeading())
)
);
path.setConstantHeadingInterpolation(Math.PI);
dt.follower.followPath(path);
state = AutoState.INTAKE;
}

@Override
public void loop() {
shooter.flywheel.adaptive(
dt.follower.getPose().getX(),
dt.follower.getPose().getY()
);
shooter.turret.loop(
dt.follower.getPose().getX(),
dt.follower.getPose().getX(),
dt.follower.getHeading()
);
dt.update();

if (!dt.follower.isBusy()) {
if (!dt.follower.isBusy() && state.equals(AutoState.INTAKE)) {
intake.run();
dt.follower.breakFollowing();
Path path1 = new Path(
new BezierLine(
Expand All @@ -49,6 +67,16 @@ public void loop() {
dt.follower.followPath(
path1
);
state = AutoState.SHOOT;
}
else if (!dt.follower.isBusy() && state.equals(AutoState.SHOOT)) {
dt.follower.breakFollowing();
intake.stop();
transfer.fireSortedArtifacts();
}
}
enum AutoState {
INTAKE,
SHOOT
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ public void start() {
MatchSettings.start();

// Start the first path
dt.follower.followPath(pathSequence[0]);
dt.follower.followPath(pathSequence[currentPathIndex]);
}

@Override
Expand Down Expand Up @@ -108,7 +108,9 @@ private void handleSubsystems() {
// Only run shooter/transfer when we've arrived at the shooting position
if (!dt.follower.isBusy()) {
// Spin up flywheel and update shooter
shooter.runLoop(dt.follower.getPose().getX(), dt.follower.getPose().getY(), dt.follower.getPose().getHeading());
shooter.runLoop(dt.follower.getPose(),
dt.follower.getVelocity()
);
shooter.flywheel.update(shooterSpeed);
shooter.tilt.setTilt(tiltPos);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ public void init() {
shoot = false;

transfer = new Kicker(hardwareMap);
shooter = new Flywheel(hardwareMap);
shooter = new Flywheel(hardwareMap, new AllianceColor(AllianceColor.Selection.BLUE));
intake = new Intake(hardwareMap);
//time = new ElapsedTime();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ public void init() {
shoot= false;

transfer = new Kicker(hardwareMap);
shooter = new Flywheel(hardwareMap);
shooter = new Flywheel(hardwareMap, new AllianceColor(AllianceColor.Selection.BLUE));
intake = new Intake(hardwareMap);
//time = new ElapsedTime();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ public void init() {
shoot = false;

transfer = new Kicker(hardwareMap);
shooter = new Flywheel(hardwareMap);
shooter = new Flywheel(hardwareMap, new AllianceColor(AllianceColor.Selection.BLUE));
intake = new Intake(hardwareMap);
//time = new ElapsedTime();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,19 +47,39 @@ public class Constants {
0.025,
0.024
))
.translationalPIDFSwitch(4)
.drivePIDFCoefficients(new FilteredPIDFCoefficients(
.6,
0,
0.025,
0.6,
0.024))
.secondaryTranslationalPIDFCoefficients(new PIDFCoefficients(
0,
0,
0.005,
0.0006
))
.headingPIDFCoefficients(new PIDFCoefficients(
1.78,
0.00,
0.055,
0.025
))
.drivePIDFCoefficients(new FilteredPIDFCoefficients(
0.75,
.secondaryHeadingPIDFCoefficients(new PIDFCoefficients(
0.0,
0,
0.005,
0.1,
0.0005
))
.secondaryDrivePIDFCoefficients(new FilteredPIDFCoefficients(
0.0,
0,
0.000005,
0.6,
0.025
0.01
))
.drivePIDFSwitch(15)
.centripetalScaling(0.0005)
.useSecondaryDrivePIDF(false)
.useSecondaryHeadingPIDF(false)
Expand All @@ -84,11 +104,11 @@ public class Constants {
.encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)
.forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD)
.strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD)
.forwardPodY(0.157480315)
.strafePodX(7.5590551181);
.forwardPodY(-7.5590551181)
.strafePodX(0.157480315);


public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1);
public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1.65, 1);

public static Follower createFollower(HardwareMap hardwareMap) {
return new FollowerBuilder(followerConstants, hardwareMap)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
package org.firstinspires.ftc.teamcode.pedroPathing.tuners;

import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.draw;
import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.drawOnlyCurrent;
import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.follower;


import com.pedropathing.geometry.BezierCurve;
import com.pedropathing.geometry.Pose;
import com.pedropathing.paths.Path;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

/**
* This is the Centripetal Tuner OpMode. It runs the robot in a specified distance
* forward and to the left. On reaching the end of the forward Path, the robot runs the backward
* Path the same distance back to the start. Rinse and repeat! This is good for testing a variety
* of Vectors, like the drive Vector, the translational Vector, the heading Vector, and the
* centripetal Vector.
*
* @author Baron Henderson - 20077 The Indubitables
* @author Anyi Lin - 10158 Scott's Bots
* @author Aaron Yang - 10158 Scott's Bots
* @author Harrison Womack - 10158 Scott's Bots
* @author Atharv Gurnnai - 13085 Bionic Dutch
* @version 1.0, 3/13/2024
*/
@TeleOp(name="Centripetal Coefficient Tuner", group="tuners")

public class Centripetaluner extends OpMode {
public double DISTANCE = 20;
private boolean forward = true;

private Path forwards;
private Path backwards;

@Override
public void init() {
follower.setStartingPose(new Pose(72, 72));
}

/**
* This initializes the Follower and creates the forward and backward Paths.
* Additionally, this initializes the Panels telemetry.
*/
@Override
public void init_loop() {
telemetry.addLine("This will run the robot in a curve going " + DISTANCE + " inches to the left and the same number of inches forward.");
telemetry.addLine("The robot will go continuously along the path.");
telemetry.addLine("Make sure you have enough room.");
telemetry.update();
follower.update();
drawOnlyCurrent();
}

@Override
public void start() {
follower.startTeleopDrive(false);
follower.activateAllPIDFs();
forwards = new Path(new BezierCurve(new Pose(72,72), new Pose(Math.abs(DISTANCE) + 72,72), new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72)));
backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72), new Pose(Math.abs(DISTANCE) + 72,72), new Pose(72,72)));

backwards.setTangentHeadingInterpolation();
backwards.reverseHeadingInterpolation();

follower.followPath(forwards);
}

/**
* This runs the OpMode, updating the Follower as well as printing out the debug statements to
* the Telemetry, as well as the Panels.
*/
@Override
public void loop() {
follower.update();
draw();
if (!follower.isBusy()) {
if (forward) {
forward = false;
follower.followPath(backwards);
} else {
forward = true;
follower.followPath(forwards);
}
}

telemetry.addLine("Driving away from the origin along the curve?: " + forward);
telemetry.update();
}
}

Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,10 @@
* @author Anyi Lin - 10158 Scott's Bots
* @author Aaron Yang - 10158 Scott's Bots
* @author Harrison Womack - 10158 Scott's Bots
* @author Atharv Gurnani - 13085 Bionic Dutch
* @version 1.0, 3/12/2024
*/
@TeleOp(name="DrivePIDF", group="tuners")
@TeleOp(name="Drive PIDF Tuner", group="tuners")
public class DrivePIDF extends OpMode {
public static double DISTANCE = 40;
private boolean forward = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

import org.firstinspires.ftc.teamcode.pedroPathing.Constants;

@TeleOp(name="ForwardTuner")
@TeleOp(name="Forward Encoder Tuner", group="tuners")
public class ForwardTner extends OpMode {
private Follower follower;
public static double DISTANCE = 48;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,10 @@
* @author Aaron Yang - 10158 Scott's Bots
* @author Harrison Womack - 10158 Scott's Bots
* @author Baron Henderson - 20077 The Indubitables
* @author Chetan Vanam - 13085 Bionic Dutch
* @version 1.0, 3/13/2024
*/
@TeleOp(name="ForwardVelocity", group="tuners")
@TeleOp(name="Forward Velocity Tuner", group="tuners")
public class ForwardVlocity extends OpMode {
private final ArrayList<Double> velocities = new ArrayList<>();
static ArrayList<String> changes = new ArrayList<>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,10 @@
* @author Baron Henderson - 20077 The Indubitables
* @author Aaron Yang - 10158 Scott's Bots
* @author Harrison Womack - 10158 Scott's Bots
* @author Atharv Gurnani - 13085 Bionic Dutch
* @version 1.0, 3/13/2024
*/
@TeleOp(name="ForwardZPAM", group="tuners")
@TeleOp(name="Forward ZPAM Tuner", group="tuners")
public class ForwardZPAM extends OpMode {
static ArrayList<String> changes = new ArrayList<>();
private Follower follower;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,10 @@
* @author Anyi Lin - 10158 Scott's Bots
* @author Aaron Yang - 10158 Scott's Bots
* @author Harrison Womack - 10158 Scott's Bots
* @author Atharv Gurnani - 13085 Bionic Dutch
* @version 1.0, 3/12/2024
*/
@TeleOp(name="HeadingPIDF", group="tuners")
@TeleOp(name="Heading PIDF Tuner", group="tuners")
public class HeadingPIDF extends OpMode {
public static double DISTANCE = 40;
private boolean forward = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,10 @@
*
* @author Anyi Lin - 10158 Scott's Bots
* @author Baron Henderson - 20077 The Indubitables
* @author Atharv Gurnani - 13085 Bionic Dutch
* @version 2.0, 6/26/2025
*/
@TeleOp(name="LateralTuner", group="tuners")
@TeleOp(name="Lateral Encoder Tuner", group="tuners")
public class LateralTner extends OpMode {
public static double DISTANCE = 48;
private Follower follower;
Expand Down
Loading