Skip to content
This repository has been archived by the owner on Jan 27, 2025. It is now read-only.

Commit

Permalink
Fixed Dir Paths. Please check your own local repos to see if you mess…
Browse files Browse the repository at this point in the history
…ed up somewhere.
  • Loading branch information
GNSRobotics2638 committed Feb 3, 2024
1 parent d2bdbb1 commit bb1d305
Show file tree
Hide file tree
Showing 151 changed files with 131 additions and 131 deletions.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,37 +1,37 @@
package frc.robot.commands.audio;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.audio.AudioPlayer;

public class playMusic extends Command {
private AudioPlayer audioPlayerSubsystem;
private int toggle;
private int maxBound;

public playMusic(AudioPlayer audioplayerSubsystem) {
this.audioPlayerSubsystem = audioplayerSubsystem;
this.toggle = 0;
this.maxBound = 2; // exclusive, also maxBound is silent
addRequirements(audioplayerSubsystem);
}

@Override
public void execute() {
System.err.println(this.toggle);
if (this.toggle == this.maxBound) {
this.audioPlayerSubsystem.stop();
this.toggle = 0;
}
else {
this.audioPlayerSubsystem.play(this.toggle);
this.toggle++;
}

// this.audioPlayerSubsystem.play(0);
}

@Override
public boolean isFinished() {
return true;
}
}
package frc.robot.commands.audio;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.audio.AudioPlayer;

public class playMusic extends Command {
private AudioPlayer audioPlayerSubsystem;
private int toggle;
private int maxBound;

public playMusic(AudioPlayer audioplayerSubsystem) {
this.audioPlayerSubsystem = audioplayerSubsystem;
this.toggle = 0;
this.maxBound = 2; // exclusive, also maxBound is silent
addRequirements(audioplayerSubsystem);
}

@Override
public void execute() {
System.err.println(this.toggle);
if (this.toggle == this.maxBound) {
this.audioPlayerSubsystem.stop();
this.toggle = 0;
}
else {
this.audioPlayerSubsystem.play(this.toggle);
this.toggle++;
}

// this.audioPlayerSubsystem.play(0);
}

@Override
public boolean isFinished() {
return true;
}
}
Original file line number Diff line number Diff line change
@@ -1,56 +1,56 @@
// package frc.robot.commands.shooter;

// import edu.wpi.first.wpilibj2.command.Command;
// import edu.wpi.first.math.geometry.Pose3d;
// import edu.wpi.first.math.geometry.Pose2d;
// import edu.wpi.first.math.geometry.Rotation3d;

// import frc.robot.subsystems.shooter.Shooter;
// import frc.robot.subsystems.swerve.SwerveSubsystem;
// import frc.robot.subsystems.aprilTagVision.AprilTagVision;

// public class AlignWithTargetPoint extends Command {
// private final Shooter shooterSubsystem;
// private final AprilTagVision visionSubsystem;
// private final Pose3d shooterPose;
// private final SwerveSubsystem swerveSubsystem;

// public AlignWithTargetPoint(Shooter shooterSubsystem, AprilTagVision visionSubsystem, SwerveSubsystem swerveSubsystem) {
// this.shooterSubsystem = shooterSubsystem;
// this.visionSubsystem = visionSubsystem;
// this.swerveSubsystem = swerveSubsystem;
// this.shooterPose = new Pose3d(0,0,0,new Rotation3d(0,0,0)); // first three zeroes are real measurments, no euler angles (rot. at tip)
// addRequirements(shooterSubsystem);
// addRequirements(visionSubsystem);
// addRequirements(swerveSubsystem);
// }

// @override
// public void execute() {
// Pose3d initialPose = new Pose3d(this.swerveSubsystem.getPose());
// Pose3d targetPointPose = this.visionSubsystem.getValidShotPoint().relativeTo(currPose); // getValidShotPoint() is the whole LL3 quad detection thing... WIP

// Pose2d drivebasePose = new Pose2d(initialPose.getX(),
// this.shooterPose.getX()*targetPointPose.getZ()/targetPointPose.getX()
// ) // no need for Y axis

// // 0,0,acos(dot(target,shooter)/(mag(target)*mag(shooter))) - roll,pitch,yaw
// // can use Rot3d and then apply as a transform to currPose and then supply transformed pose (time benefits?)

// this.swerveSubsystem.drive(drivebasePose.getTranslation(), drivebasePose.getRotation(), true, false); // 1st boolean might be wrong
// // the drivebase theoretically just rotated in place to to remove the z axis

// while (this.shooterPose.getX()/targetPointPose.getX() != this.shooterPose.getZ()/targetPointPose.getZ()) { // the variable to eliminate is Z, since Z is in place of Y
// if () {}
// else {}
// targetPointPose = this.visionSubsystem.getValidShotPoint().relativeTo(new Pose3d(this.swerveSubsystem.getPose())); // doesn't exist... yet
// }

// }

// @Override
// public boolean isFinished() {
// return false;
// }

// package frc.robot.commands.shooter;

// import edu.wpi.first.wpilibj2.command.Command;
// import edu.wpi.first.math.geometry.Pose3d;
// import edu.wpi.first.math.geometry.Pose2d;
// import edu.wpi.first.math.geometry.Rotation3d;

// import frc.robot.subsystems.shooter.Shooter;
// import frc.robot.subsystems.swerve.SwerveSubsystem;
// import frc.robot.subsystems.aprilTagVision.AprilTagVision;

// public class AlignWithTargetPoint extends Command {
// private final Shooter shooterSubsystem;
// private final AprilTagVision visionSubsystem;
// private final Pose3d shooterPose;
// private final SwerveSubsystem swerveSubsystem;

// public AlignWithTargetPoint(Shooter shooterSubsystem, AprilTagVision visionSubsystem, SwerveSubsystem swerveSubsystem) {
// this.shooterSubsystem = shooterSubsystem;
// this.visionSubsystem = visionSubsystem;
// this.swerveSubsystem = swerveSubsystem;
// this.shooterPose = new Pose3d(0,0,0,new Rotation3d(0,0,0)); // first three zeroes are real measurments, no euler angles (rot. at tip)
// addRequirements(shooterSubsystem);
// addRequirements(visionSubsystem);
// addRequirements(swerveSubsystem);
// }

// @override
// public void execute() {
// Pose3d initialPose = new Pose3d(this.swerveSubsystem.getPose());
// Pose3d targetPointPose = this.visionSubsystem.getValidShotPoint().relativeTo(currPose); // getValidShotPoint() is the whole LL3 quad detection thing... WIP

// Pose2d drivebasePose = new Pose2d(initialPose.getX(),
// this.shooterPose.getX()*targetPointPose.getZ()/targetPointPose.getX()
// ) // no need for Y axis

// // 0,0,acos(dot(target,shooter)/(mag(target)*mag(shooter))) - roll,pitch,yaw
// // can use Rot3d and then apply as a transform to currPose and then supply transformed pose (time benefits?)

// this.swerveSubsystem.drive(drivebasePose.getTranslation(), drivebasePose.getRotation(), true, false); // 1st boolean might be wrong
// // the drivebase theoretically just rotated in place to to remove the z axis

// while (this.shooterPose.getX()/targetPointPose.getX() != this.shooterPose.getZ()/targetPointPose.getZ()) { // the variable to eliminate is Z, since Z is in place of Y
// if () {}
// else {}
// targetPointPose = this.visionSubsystem.getValidShotPoint().relativeTo(new Pose3d(this.swerveSubsystem.getPose())); // doesn't exist... yet
// }

// }

// @Override
// public boolean isFinished() {
// return false;
// }

// }
Original file line number Diff line number Diff line change
@@ -1,39 +1,39 @@
package frc.robot.subsystems.audio;

import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;

import com.ctre.phoenix6.Orchestra;
import com.ctre.phoenix6.hardware.ParentDevice;
import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class AudioPlayer extends SubsystemBase {

private Orchestra orchestra;
List<TalonFX> motors;

public AudioPlayer() {
List<ParentDevice> motors = new ArrayList<>(
Arrays.asList(new TalonFX(0, "rio"), new TalonFX(1, "rio"), new TalonFX(2, "rio"), new TalonFX(3, "rio"),
new TalonFX(4, "rio"), new TalonFX(5, "rio"), new TalonFX(6, "rio"), new TalonFX(7, "rio")));

orchestra = new Orchestra(motors);

}

public void play(int songID) {
orchestra.loadMusic(Integer.toString(songID)+".chrp");
orchestra.play();
// System.out.println("here");
}

public void stop() {
orchestra.stop();
}

}
package frc.robot.subsystems.audio;

import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;

import com.ctre.phoenix6.Orchestra;
import com.ctre.phoenix6.hardware.ParentDevice;
import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class AudioPlayer extends SubsystemBase {

private Orchestra orchestra;
List<TalonFX> motors;

public AudioPlayer() {
List<ParentDevice> motors = new ArrayList<>(
Arrays.asList(new TalonFX(0, "rio"), new TalonFX(1, "rio"), new TalonFX(2, "rio"), new TalonFX(3, "rio"),
new TalonFX(4, "rio"), new TalonFX(5, "rio"), new TalonFX(6, "rio"), new TalonFX(7, "rio")));

orchestra = new Orchestra(motors);

}

public void play(int songID) {
orchestra.loadMusic(Integer.toString(songID)+".chrp");
orchestra.play();
// System.out.println("here");
}

public void stop() {
orchestra.stop();
}

}
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.

0 comments on commit bb1d305

Please sign in to comment.