Skip to content

Commit

Permalink
WPILIB and PathPlannerLib Updates
Browse files Browse the repository at this point in the history
  • Loading branch information
Mallen220 committed Mar 29, 2024
1 parent 095f4ef commit 50a7729
Show file tree
Hide file tree
Showing 6 changed files with 22 additions and 27 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.3.1"
id "edu.wpi.first.GradleRIO" version "2024.3.2"
id 'com.diffplug.spotless' version '6.25.0'
}

Expand Down
30 changes: 13 additions & 17 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.ConditionalCommand;
import edu.wpi.first.wpilibj2.command.InstantCommand;
Expand All @@ -42,8 +41,6 @@
import frc.robot.commands.control.ShootSubwooferFlat;
import frc.robot.commands.control.ShootTall;
import frc.robot.commands.control.StopAll;
import frc.robot.commands.control.amp.FireRevAmp;
import frc.robot.commands.control.amp.PrepRevAmp;
import frc.robot.commands.control.auto.AutoAimLockWrist;
import frc.robot.commands.control.auto.AutoIdleShooter;
import frc.robot.commands.control.auto.InstantShoot;
Expand All @@ -58,7 +55,6 @@
import frc.robot.commands.movement.CollectNoteAuto;
import frc.robot.commands.movement.DriveToNote;
import frc.robot.commands.movement.DriveToNoteAuto;
import frc.robot.commands.movement.PointAtAprilTag;
import frc.robot.commands.movement.SwerveCommand;
import frc.robot.commands.qol.AsyncRumble;
import frc.robot.commands.qol.DefaultCANdle;
Expand Down Expand Up @@ -122,7 +118,7 @@ public RobotContainer() {
configureShuffleboard();
configureDrivetrain();
configureDriverController();
//configureCoDriverController();
// configureCoDriverController();
configureDefaultCommands();
}

Expand Down Expand Up @@ -548,18 +544,18 @@ public void updatePoseVision() {
// if (poseRight.tagCount >= 2) {
// DRIVETRAIN.addVisionMeasurement(
// poseRight.pose, poseRight.timestampSeconds, VecBuilder.fill(1.5, 1.5,1.5));
// } else {
// if (pose.rawFiducials.length > 0 && pose.rawFiducials[0].ambiguity < 0.07) {
// DriverStation.reportWarning(
// "ADDING POSE BASED ON AMBIGUITY OF "
// + pose.rawFiducials[0].ambiguity
// + " ON TAG "
// + pose.rawFiducials[0].id,
// false);
// DRIVETRAIN.addVisionMeasurement(
// pose.pose, pose.timestampSeconds, VecBuilder.fill(.7, .7, 9999999));
// }
//}
// } else {
// if (pose.rawFiducials.length > 0 && pose.rawFiducials[0].ambiguity < 0.07) {
// DriverStation.reportWarning(
// "ADDING POSE BASED ON AMBIGUITY OF "
// + pose.rawFiducials[0].ambiguity
// + " ON TAG "
// + pose.rawFiducials[0].id,
// false);
// DRIVETRAIN.addVisionMeasurement(
// pose.pose, pose.timestampSeconds, VecBuilder.fill(.7, .7, 9999999));
// }
// }
}

public static RobotContainer get() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public void initialize() {}
public void execute() {
double degrees = Util.getInterpolatedWristAngle();
// TODO find actual values, prevent wrist collision when the elevator is all the way down.
DriverStation.reportWarning("Wrist Degrees Angle " + degrees, false);
DriverStation.reportWarning("Wrist Degrees Angle " + degrees, false);
if (degrees > 10.0 && degrees < 35.0) {

return;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
package frc.robot.commands.control.auto;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.RobotContainer;
import frc.robot.constants.Constants;
import frc.robot.subsystems.Shooter;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,11 +148,11 @@ public Optional<Rotation2d> getRotationTargetOverride() {
if (RobotContainer.aimAtTargetAuto) {
Pose2d current = getPose();
double desiredRotation =
current.getRotation().minus(Util.getRotationToAllianceSpeaker(current)).getDegrees();
current.getRotation().minus(Util.getRotationToAllianceSpeaker(current)).getDegrees();

// drivetrain.setChassisSpeeds(HOLO_CONTROLLER.calculate(current, new
// Pose2d(current.getTranslation(), new Rotation2d(desiredRotation)), 0, new
// Rotation2d(desiredRotation)));
// drivetrain.setChassisSpeeds(HOLO_CONTROLLER.calculate(current, new
// Pose2d(current.getTranslation(), new Rotation2d(desiredRotation)), 0, new
// Rotation2d(desiredRotation)));
return Optional.of(Rotation2d.fromDegrees(desiredRotation + 90.0));
} else {
// return an empty optional when we don't want to override the path's rotation
Expand Down
6 changes: 3 additions & 3 deletions vendordeps/PathplannerLib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2024.2.7",
"version": "2024.2.8",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2024.2.7"
"version": "2024.2.8"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2024.2.7",
"version": "2024.2.8",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down

0 comments on commit 50a7729

Please sign in to comment.