Skip to content

Commit

Permalink
Merge pull request #101 from robototes/full-target-tuning
Browse files Browse the repository at this point in the history
Full target tuning
  • Loading branch information
TAKBS2412 authored Apr 3, 2024
2 parents 634338e + 2e4fdc7 commit 8fdd36a
Show file tree
Hide file tree
Showing 5 changed files with 79 additions and 14 deletions.
34 changes: 26 additions & 8 deletions src/main/deploy/launcher_data.csv
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,29 @@

# DISTANCE (meters), ANGLE (degrees), RPM (velocity)

1.397, 254, 4500
2.05, 249, 4500
2.6, 245, 4500
3.2, 243, 4500
5, 240, 5000
5.64,239, 5000
6, 238, 5000
14, 233, 5000
# These RPMs are target RPMs, actual was much lower

# Front subwoofer
1.30, 254, 3500
# Front bumper at autoline
2.13, 250, 3500
# Near podium
5.66, 246, 3600
# Auto point 1 (X 2.870, Y 2.196, theta 130.6)
4.46, 242, 3600

# After this, these are setpoint angles
# Auto point 2 (X 5.699, Y 7.501, theta -162.8)
5.55, 240.3, 4400
# Auto point 3 (X 4.299, Y 5.134, theta 176.222)
4.32, 242, 4300 # Might be a little low, and could probably lower RPM- Ran out of time to fully test

# Pre 3/28 values:
# 1.397, 254, 4500
# 2.05, 249, 4500
# 2.6, 245, 4500
# 3.2, 243, 4500
# 5, 240, 5000
# 5.64,239, 5000
# 6, 238, 5000
# 14, 233, 5000
18 changes: 18 additions & 0 deletions src/main/java/frc/team2412/robot/Controls.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,12 @@
import static frc.team2412.robot.Subsystems.SubsystemConstants.LED_ENABLED;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
Expand Down Expand Up @@ -108,6 +110,22 @@ public Controls(Subsystems s) {
if (LED_ENABLED) {
bindLEDControls();
}
Pose2d SPEAKER_POSE =
Robot.isBlue()
? new Pose2d(0.0, 5.55, Rotation2d.fromRotations(0))
: new Pose2d(16.5, 5.55, Rotation2d.fromRotations(0));
if (DRIVEBASE_ENABLED && LAUNCHER_ENABLED) {
Commands.run(
() -> {
Pose2d robotPose = s.drivebaseSubsystem.getPose();
Pose2d relativeSpeaker = robotPose.relativeTo(SPEAKER_POSE);
double distance = relativeSpeaker.getTranslation().getNorm();
s.launcherSubsystem.updateDistanceEntry(distance);
})
.withName("Update distance")
.ignoringDisable(true)
.schedule();
}
if (DRIVEBASE_ENABLED && LAUNCHER_ENABLED && INTAKE_ENABLED) {
// temporary controls, not sure what drive team wants
driveController
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/team2412/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import com.ctre.phoenix6.SignalLogger;
import edu.wpi.first.wpilibj.DataLogManager;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj.RobotBase;
Expand Down Expand Up @@ -207,4 +208,12 @@ public static boolean isDebugMode() {
public static boolean isSysIdMode() {
return sysIdMode;
}

public static boolean isBlue() {
return DriverStation.getAlliance().orElse(Alliance.Red) == Alliance.Blue;
}

public static boolean isRed() {
return DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.team2412.robot.Hardware;
import frc.team2412.robot.Robot;
Expand Down Expand Up @@ -89,6 +90,8 @@ public class LauncherSubsystem extends SubsystemBase {

private GenericEntry setLauncherSpeedEntry;

private GenericEntry setLauncherAngleEntry;

private GenericEntry launcherAngleEntry;

private GenericEntry launcherSpeedEntry;
Expand Down Expand Up @@ -340,9 +343,13 @@ private void initShuffleboard() {
.withPosition(5, 0)
.getEntry();

setLauncherAngleEntry =
Shuffleboard.getTab("Launcher").add("Launcher Angle Setpoint", getAngle()).getEntry();

launcherAngleManual =
Shuffleboard.getTab("Launcher")
.add("Launcher manual increase", 0)
.add("Launcher manual angle (rot.)", 0)
.withPosition(0, 1)
.withSize(1, 1)
.withWidget(BuiltInWidgets.kTextView)
.getEntry();
Expand All @@ -362,6 +369,19 @@ private void initShuffleboard() {
Shuffleboard.getTab("Launcher").add("Angle Setpoint", 0).withPosition(2, 2).getEntry();
launcherFlywheelSetpointEntry =
Shuffleboard.getTab("Launcher").add("Flywheel Setpoint", 0).withPosition(4, 5).getEntry();

var manualModeEntry =
Shuffleboard.getTab("Launcher")
.add("Full manual mode", false)
.withPosition(3, 0)
.getEntry();
new Trigger(() -> manualModeEntry.getBoolean(false))
.whileTrue(
run(() -> {
setAngle(setLauncherAngleEntry.getDouble(getAngle()));
launch(setLauncherSpeedEntry.getDouble(SPEAKER_SHOOT_SPEED_RPM));
})
.withName("Full Manual"));
}

public void updateDistanceEntry(double distance) {
Expand Down
10 changes: 5 additions & 5 deletions vendordeps/REVLib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2024.2.1",
"version": "2024.2.3",
"frcYear": "2024",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
Expand All @@ -12,14 +12,14 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2024.2.1"
"version": "2024.2.3"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2024.2.1",
"version": "2024.2.3",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
Expand All @@ -37,7 +37,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2024.2.1",
"version": "2024.2.3",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand All @@ -55,7 +55,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2024.2.1",
"version": "2024.2.3",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down

0 comments on commit 8fdd36a

Please sign in to comment.