Skip to content

Commit

Permalink
Start beta updates
Browse files Browse the repository at this point in the history
  • Loading branch information
pjreiniger committed Oct 13, 2024
1 parent d14c547 commit af7657f
Show file tree
Hide file tree
Showing 9 changed files with 44 additions and 18 deletions.
2 changes: 1 addition & 1 deletion MODULE.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ bazel_dep(name = "rules_bazelrio", version = "0.0.14")
bazel_dep(name = "rules_bzlmodrio_toolchains", version = "2024-1")
bazel_dep(name = "rules_bzlmodrio_jdk", version = "17.0.8.1-1")
bazel_dep(name = "rules_pmd", version = "7.2.0")
bazel_dep(name = "bzlmodrio-allwpilib", version = "2024.3.2")
bazel_dep(name = "bzlmodrio-allwpilib", version = "2025.1.1-beta-1")
bazel_dep(name = "bzlmodrio-navx", version = "2024.1.0")
bazel_dep(name = "bzlmodrio-phoenix", version = "5.33.1")
bazel_dep(name = "bzlmodrio-phoenix6", version = "24.0.0-beta-8")
Expand Down
2 changes: 1 addition & 1 deletion build_scripts/base_java.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ ext.getCurrentOs = {
}

ext {
wpiVersion = '2024.3.2'
wpiVersion = '2025.1.1-beta-1'
opencvYear = '2024'
opencvVersion = '4.8.0-1'
phoenix5Version = '5.33.1'
Expand Down
8 changes: 5 additions & 3 deletions build_scripts/bazel/deps/download_external_archives.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,13 @@ load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive")

def download_external_archives():
# Download bzlmodRio <3
BZLMODRIO_COMMITISH = "5fc8b394699149fe870963e26ea672d2b00dfa37"
BZLMODRIO_SHA256 = "b09a5f93efb7231212f87038dfb30146d6ed9f26007349ba2a0c532d3976e675"
http_archive(
name = "bzlmodrio",
url = "https://github.com/bzlmodRio/bzlmodRio/archive/17983128beaeb12f184d22a426fecd8b536a5452.tar.gz",
sha256 = "aec41ceddbb412c32202ec84246ca5e65fa41325693f8bfc27e2c44c756f66a6",
strip_prefix = "bzlmodRio-17983128beaeb12f184d22a426fecd8b536a5452",
url = "https://github.com/bzlmodRio/bzlmodRio/archive/{}.tar.gz".format(BZLMODRIO_COMMITISH),
sha256 = BZLMODRIO_SHA256,
strip_prefix = "bzlmodRio-{}".format(BZLMODRIO_COMMITISH),
)
# native.local_repository(
# name = "bzlmodrio",
Expand Down
2 changes: 1 addition & 1 deletion build_scripts/bazel/deps/setup_dependencies.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ load("@bzlmodrio//private/non_bzlmod:download_dependencies.bzl", "download_depen
def setup_dependencies():
download_dependencies(
# toolchain_versions = "2024-1",
allwpilib_version = "2024.3.2",
allwpilib_version = "2025.1.1-beta-1",
# ni_version = "2024.1.1",
# opencv_version = "2024.4.8.0-1",
revlib_version = "2024.2.4",
Expand Down
Original file line number Diff line number Diff line change
@@ -1,27 +1,39 @@
package org.snobotv2.examples.base.commands.auton;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import edu.wpi.first.wpilibj2.command.Command;
import org.snobotv2.examples.base.subsystems.DrivetrainSubsystem;

public class TurnToAngle extends PIDCommand
public class TurnToAngle extends Command
{
private final PIDController mController;
private final DrivetrainSubsystem mDrivetrain;
private final double mGoal;

@SuppressWarnings("PMD.ConstructorCallsOverridableMethod")
public TurnToAngle(DrivetrainSubsystem drivetrain, double goal)
{
super(new PIDController(.02, 0, 0.001),
drivetrain::getHeadingDegrees,
goal,
(double output) -> drivetrain.arcadeDrive(0, output),
drivetrain);
mController = new PIDController(.02, 0, 0.001);
mController.enableContinuousInput(-180, 180);
mController.setTolerance(3, 1);

mDrivetrain = drivetrain;
mGoal = goal;

addRequirements(mDrivetrain);
}

getController().enableContinuousInput(-180, 180);
getController().setTolerance(3, 1);
@Override
public void execute()
{
double currentAngle = mDrivetrain.getHeadingDegrees();
double output = mController.calculate(currentAngle, mGoal);
mDrivetrain.arcadeDrive(0, output);
}

@Override
public boolean isFinished()
{
return m_controller.atSetpoint();
return mController.atSetpoint();
}
}
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
package org.snobotv2.examples.base.subsystems;

import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj2.command.Subsystem;
Expand All @@ -14,7 +17,9 @@ final class FlywheelSimConstants

public static FlywheelSim createSim()
{
return new FlywheelSim(kGearbox, kGearing, kInertia);
LinearSystem<N1, N1, N1> plant =
LinearSystemId.createFlywheelSystem(kGearbox, kInertia, kGearing);
return new FlywheelSim(plant, kGearbox);
}

private FlywheelSimConstants()
Expand Down
1 change: 1 addition & 0 deletions examples/test_robot_rev/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ dependencies {
implementation wpilibTools.deps.wpilibJava("hal")
implementation wpilibTools.deps.wpilibJava("wpilibj")
implementation wpilibTools.deps.wpilibJava("wpimath")
implementation wpilibTools.deps.wpilibJava("wpiunits")
implementation wpilibTools.deps.wpilibJava("wpiutil")
implementation wpilibTools.deps.wpilibJava("cscore")
implementation wpilibTools.deps.wpilibJava("ntcore")
Expand Down
1 change: 1 addition & 0 deletions examples/test_robot_wpi/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ apply from: "${rootDir}/build_scripts/base_java.gradle"
dependencies {
implementation wpilibTools.deps.wpilibJava("wpilibj")
implementation wpilibTools.deps.wpilibJava("wpimath")
implementation wpilibTools.deps.wpilibJava("wpiunits")
implementation wpilibTools.deps.wpilibJava("hal")
implementation wpilibTools.deps.wpilibJava("wpiutil")
implementation wpilibTools.deps.wpilibJava("cameraserver")
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
package edu.wpi.first.wpilibj.simulation.swerve;

import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;


Expand All @@ -16,7 +19,9 @@ class SimpleMotorWithMassModel {
* @param moi Moment of inertia of the controlled mass
*/
SimpleMotorWithMassModel(DCMotor motor, double gearing, double moi) {
m_fwSim = new FlywheelSim(motor, gearing, moi);
LinearSystem<N1, N1, N1> plant =
LinearSystemId.createFlywheelSystem(motor, moi, gearing);
m_fwSim = new FlywheelSim(plant, motor);
}

void update(double motorVoltage, double dtSeconds) {
Expand Down

0 comments on commit af7657f

Please sign in to comment.