Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,5 @@
/build
/captures
.externalNativeBuild
/node_modules

6 changes: 2 additions & 4 deletions Path/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ android {
targetSdkVersion 28
}

compileSdkVersion 29
compileSdkVersion 34

compileOptions {
sourceCompatibility JavaVersion.VERSION_1_8
Expand All @@ -31,11 +31,9 @@ dependencies {

implementation 'org.apache.commons:commons-math3:3.6.1'


implementation 'com.acmerobotics.dashboard:dashboard:0.4.15'
implementation 'com.acmerobotics.dashboard:dashboard:0.4.16'
implementation 'com.acmerobotics.roadrunner:core:0.5.6'


testImplementation(platform('org.junit:junit-bom:5.7.0'))
testImplementation('org.junit.jupiter:junit-jupiter-api:5.7.0')
testRuntimeOnly('org.junit.jupiter:junit-jupiter-engine:5.7.0')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
import com.technototes.library.hardware.HardwareDevice;
import com.technototes.library.hardware.motor.EncodedMotor;
import com.technototes.library.hardware.sensor.IGyro;
import com.technototes.library.hardware.sensor.IMU;
import com.technototes.library.subsystem.Subsystem;
import com.technototes.path.subsystem.MecanumConstants.GearRatio;
import com.technototes.path.subsystem.MecanumConstants.HeadPID;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
import com.qualcomm.robotcore.hardware.VoltageSensor;
import com.technototes.library.hardware.HardwareDevice;
import com.technototes.library.hardware.motor.EncodedMotor;
import com.technototes.library.hardware.sensor.IMU;
import com.technototes.library.hardware.sensor.IGyro;
import com.technototes.library.subsystem.Subsystem;
import com.technototes.path.subsystem.TankConstants.*;
import com.technototes.path.trajectorysequence.TrajectorySequence;
Expand Down Expand Up @@ -59,14 +59,14 @@ public class TankDrivebaseSubsystem extends TankDrive implements Subsystem {
private TrajectoryFollower follower;

private List<EncodedMotor<DcMotorEx>> motors, leftMotors, rightMotors;
private IMU imu;
private IGyro imu;

private VoltageSensor batteryVoltageSensor;

public TankDrivebaseSubsystem(
List<EncodedMotor<DcMotorEx>> left,
List<EncodedMotor<DcMotorEx>> right,
IMU i,
IGyro i,
TankConstants c,
Localizer localizer
) {
Expand Down Expand Up @@ -300,7 +300,7 @@ public void setMotorPowers(double v, double v1) {

@Override
public double getRawExternalHeading() {
return imu.getAngularOrientation(AngleUnit.RADIANS).firstAngle;
return imu.getHeading();
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,8 @@

import androidx.annotation.NonNull;
import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer;
import com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer;
import com.technototes.library.hardware.sensor.IMU;
import com.technototes.library.hardware.sensor.IGyro;
import com.technototes.library.hardware.sensor.encoder.MotorEncoder;
import com.technototes.library.subsystem.Subsystem;
import java.util.Arrays;
Expand Down Expand Up @@ -40,7 +39,7 @@ public class TwoDeadWheelLocalizer extends TwoTrackingWheelLocalizer implements

protected boolean encoderOverflow;

public TwoDeadWheelLocalizer(IMU imu, MotorEncoder lr, MotorEncoder fb, DeadWheelConstants constants) {
public TwoDeadWheelLocalizer(IGyro imu, MotorEncoder lr, MotorEncoder fb, DeadWheelConstants constants) {
super(
Arrays.asList(
new Pose2d(0, constants.getDouble(LateralDistance.class), 0), // left
Expand Down
2 changes: 1 addition & 1 deletion RobotLibrary/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ android {
targetSdkVersion 28
}

compileSdkVersion 29
compileSdkVersion 34

compileOptions {
sourceCompatibility JavaVersion.VERSION_1_8
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
package com.technototes.library.command;

/**
* Each time this command(group) is scheduled, the next one
* in the series will execute. When the last one is executed,
* it starts over at the first one.
*
* The most obvious application is for "toggle" command:
* something like this:
* clawToggle = new CycleCommandGroup(claw::open, claw::close);
*/
public class CycleCommandGroup implements Command {
protected Command[] commands;
protected int currentState = 0;

public CycleCommandGroup(Command... commands) {
assert commands.length > 0;
this.commands = commands;
}

public void execute() {
commands[currentState].run();
currentState = (currentState + 1) % commands.length;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
package com.technototes.library.command;

import java.util.function.Consumer;

public class LinearRangeCommand extends TimedCommand {
double startVal, endVal;

public LinearRangeCommand(double time, double start, double end, Consumer<Double> func) {
super(time, func);
startVal = start;
endVal = end;
}

@Override
public void execute() {
// Being explicitly pedantic about pre-algebra, here...
double M = (endVal - startVal) / startVal;
double X = getRuntime().time();
double B = startVal;

double Y = M * X + B;

function.accept(Y);
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package com.technototes.library.command;

import java.util.function.Consumer;

public class TimedCommand extends WaitCommand {
protected double timeToRun;
protected Consumer<Double> function;

public TimedCommand(double time, Consumer<Double> func){
super(time);
function = func;
}

@Override
public void execute() {
function.accept(getRuntime().time());
}
}
2 changes: 1 addition & 1 deletion Vision/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ android {
targetSdkVersion 28
}

compileSdkVersion 29
compileSdkVersion 34

compileOptions {
sourceCompatibility JavaVersion.VERSION_1_8
Expand Down
8 changes: 4 additions & 4 deletions build.dependencies.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@ repositories {
}

dependencies {
implementation 'org.firstinspires.ftc:RobotCore:10.1.0'
implementation 'org.firstinspires.ftc:RobotServer:10.1.0'
implementation 'org.firstinspires.ftc:Hardware:10.1.0'
implementation 'org.firstinspires.ftc:FtcCommon:10.1.0'
implementation 'org.firstinspires.ftc:RobotCore:11.0.0'
implementation 'org.firstinspires.ftc:RobotServer:11.0.0'
implementation 'org.firstinspires.ftc:Hardware:11.0.0'
implementation 'org.firstinspires.ftc:FtcCommon:11.0.0'
implementation 'androidx.appcompat:appcompat:1.3.1'
}
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ buildscript {
google()
}
dependencies {
classpath 'com.android.tools.build:gradle:7.2.0'
classpath 'com.android.tools.build:gradle:8.11.1'
// NOTE: Do not place your application dependencies here; they belong
// in the individual module build.gradle files
}
Expand Down
Binary file modified bun.lockb
Binary file not shown.
25 changes: 11 additions & 14 deletions gradle.properties
Original file line number Diff line number Diff line change
@@ -1,19 +1,16 @@
# Project-wide Gradle settings.

# IDE (e.g. Android Studio) users:
# Gradle settings configured through the IDE *will override*
# any settings specified in this file.

# For more details on how to configure your build environment visit
## For more details on how to configure your build environment visit
# http://www.gradle.org/docs/current/userguide/build_environment.html

#
# Specifies the JVM arguments used for the daemon process.
# The setting is particularly useful for tweaking memory settings.
# Default value: -Xmx1024m -XX:MaxPermSize=256m
# org.gradle.jvmargs=-Xmx2048m -XX:MaxPermSize=512m -XX:+HeapDumpOnOutOfMemoryError -Dfile.encoding=UTF-8
#
# When configured, Gradle will run in incubating parallel mode.
# This option should only be used with decoupled projects. For more details, visit
# https://developer.android.com/r/tools/gradle-multi-project-decoupled-projects
# org.gradle.parallel=true
#Sun Jul 27 08:41:53 PDT 2025
android.enableJetifier=true
android.useAndroidX=true
org.gradle.jvmargs=-Xmx1536m

# When configured, Gradle will run in incubating parallel mode.
# This option should only be used with decoupled projects. More details, visit
# http://www.gradle.org/docs/current/userguide/multi_project_builds.html#sec:decoupled_projects
# org.gradle.parallel=true
org.gradle.jvmargs=-Xmx2048M -Dkotlin.daemon.jvm.options\="-Xmx2048M"
2 changes: 1 addition & 1 deletion gradle/wrapper/gradle-wrapper.properties
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#Tue Sep 27 22:08:26 PDT 2022
distributionBase=GRADLE_USER_HOME
distributionUrl=https\://services.gradle.org/distributions/gradle-7.4.2-all.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-8.13-bin.zip
distributionPath=wrapper/dists
zipStoreBase=GRADLE_USER_HOME
zipStorePath=wrapper/dists
2 changes: 1 addition & 1 deletion package.json
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
"os": "bun run scripts/os.ts"
},
"devDependencies": {
"@freik/workspace": "^0.6.4",
"@freik/workspace": "^0.6.5",
"prettier": "3.3.3",
"prettier-plugin-java": "2.6.4"
},
Expand Down