Skip to content
This repository has been archived by the owner on Nov 10, 2024. It is now read-only.

Commit

Permalink
vision shoot2
Browse files Browse the repository at this point in the history
  • Loading branch information
MorphaxTheDeveloper committed Mar 14, 2024
1 parent fcc2751 commit 4f4510d
Show file tree
Hide file tree
Showing 4 changed files with 40 additions and 6 deletions.
14 changes: 11 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,9 @@ private void configureBindings() {
//buton 1
new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(()-> m_feeder.forward()));
new JoystickButton(driverJoytick, 1).whileFalse(new InstantCommand(()-> m_feeder.stop()));
new JoystickButton(driverJoytick, 1).whileTrue(new InstantCommand(()-> m_shooter.ShooterThrowMotorOutput(0.2)));
new JoystickButton(driverJoytick, 1).whileFalse(new InstantCommand(()-> m_shooter.ShooterThrow1MotorStop()));
new JoystickButton(driverJoytick, 1).whileFalse(new InstantCommand(()-> m_shooter.ShooterThrow2MotorStop()));


//buton 2
Expand All @@ -132,6 +135,8 @@ private void configureBindings() {
new JoystickButton(driverJoytick, 7).whileFalse(new InstantCommand(()-> m_arm.leftarmstop()));
new JoystickButton(driverJoytick, 8).whileFalse(new InstantCommand(()-> m_arm.rightarmstop()));



/*
____ _ _ ____ ____ ____ __ _ _ ____ ____
/ ___)/ )( \( _ \( \( _ \( )/ )( \( __)( _ \
Expand All @@ -154,8 +159,8 @@ private void configureBindings() {
new JoystickButton(subJoytick, 2).whileFalse(new InstantCommand(()->m_intake.StopNoteMotor()));

//buton 3 Shooter Manuel subbuffer
new JoystickButton(subJoytick, 3).whileTrue(new VisionShooter(m_shooter, m_network));
new JoystickButton(subJoytick, 3).whileTrue(new InstantCommand(()-> m_shooter.ShooterThrowMotorOutput(-0.9)));
//new JoystickButton(subJoytick, 3).whileTrue(new VisionShooter(m_shooter, m_network));
new JoystickButton(subJoytick, 3).whileTrue(new InstantCommand(()-> m_shooter.ShooterThrowMotorOutput(-1)));
new JoystickButton(subJoytick, 3).whileFalse(new InstantCommand(()-> m_shooter.ShooterThrow1MotorStop()));
new JoystickButton(subJoytick, 3).whileFalse(new InstantCommand(()-> m_shooter.ShooterThrow2MotorStop()));

Expand All @@ -164,7 +169,10 @@ private void configureBindings() {

//button 5 Amfi
new JoystickButton(subJoytick, 5).whileTrue(new ShooterSetDegree(m_shooter, ()->180.0));

new JoystickButton(subJoytick, 6).whileTrue(new ShooterSetDegree(m_shooter, ()->70.0));
new JoystickButton(subJoytick, 6).whileTrue(new InstantCommand(()-> m_shooter.ShooterThrowMotorOutput(-1)));
new JoystickButton(subJoytick, 6).whileFalse(new InstantCommand(()-> m_shooter.ShooterThrow1MotorStop()));
new JoystickButton(subJoytick, 6).whileFalse(new InstantCommand(()-> m_shooter.ShooterThrow2MotorStop()));



Expand Down
12 changes: 9 additions & 3 deletions src/main/java/frc/robot/commands/Shooter/VisionShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ public VisionShooter(ShooterSubsystem m_shooter, NetworkSubsystem m_network) {
0,
Constants.values.shooter.PidShooterAngleKD),
() -> m_network.getY(),
() -> -100,
() -> -165,
output -> {
/* try {
m_shooter.ShooterAngleMotorOutput(output * .13);
Expand All @@ -25,9 +25,15 @@ public VisionShooter(ShooterSubsystem m_shooter, NetworkSubsystem m_network) {
} catch (InterruptedException e) {
e.printStackTrace();
}*/
m_shooter.ShooterAngleMotorOutput(output * .13);

});





m_shooter.ShooterAngleMotorOutput(output * .13);
});

addRequirements(m_shooter);
getController().setTolerance(5);

Expand Down
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/subsystems/NetworkSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@ public class NetworkSubsystem extends SubsystemBase {

double apriltag_x_value;
double apriltag_y_value;
boolean has_apriltag_value;


public NetworkTableInstance inst = NetworkTableInstance.getDefault();
//table
Expand All @@ -24,13 +26,18 @@ public class NetworkSubsystem extends SubsystemBase {
//entry
public NetworkTableEntry apriltag_x = networkTable.getEntry("apriltag_x");
public NetworkTableEntry apriltag_y = networkTable.getEntry("apriltag_y");
public NetworkTableEntry has_apriltag = networkTable.getEntry("has_apriltag");

public NetworkSubsystem() {
// inst.setServerTeam(7672);
//inst.startServer("10.76.72.2");
inst.setServerTeam(7672);
}

public boolean hasApriltag(){
return has_apriltag_value;
}

public double getX(){
return apriltag_x_value;
}
Expand All @@ -43,6 +50,9 @@ public double getY(){
public void periodic() {
apriltag_x_value = apriltag_x.getDouble(0.0);
apriltag_y_value = apriltag_y.getDouble(0.0);
has_apriltag_value = has_apriltag.getBoolean(false);

SmartDashboard.putBoolean("Has apriltag", has_apriltag_value);
SmartDashboard.putNumber("apriltag x value", apriltag_x_value);
SmartDashboard.putNumber("apriltag y value", apriltag_y_value);
SmartDashboard.putBoolean("connection",inst.isConnected());
Expand Down
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,16 @@ public void brakemode1() {

}

public boolean whichSide(){

if(getMappedOutput() > 90){
return true;
}
else{
return false;
}
}

public void brakemode2() {
ShooterThrowMotor2.setIdleMode(IdleMode.kBrake);

Expand Down

0 comments on commit 4f4510d

Please sign in to comment.