Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

TrapArm #12

Merged
merged 3 commits into from
Jan 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -310,4 +310,10 @@ public static class FeederConstants{
public static final double FeederMotorSpeed = 0.8;

}
public static class TrapArmConstants{
public static final int ArmMotorID = 10;
public static final int InnerSwitchID= 0;
public static final int OuterSwitchID= 10;

}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.TrapArmCommands;

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

public class goInSwitchCommand extends Command {
private final TrapArmSubsystem trapArmSubsystem= TrapArmSubsystem.getInstance();
/** Creates a new goInSwitch. */
public goInSwitchCommand() {
addRequirements(trapArmSubsystem);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
trapArmSubsystem.setSpeed(0);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return trapArmSubsystem.getInnerSwitch();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.TrapArmCommands;

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

public class goOutSwitchCommand extends Command {
private final TrapArmSubsystem trapArmSubsystem= TrapArmSubsystem.getInstance();
/** Creates a new goOutSwitch. */
public goOutSwitchCommand() {
addRequirements(trapArmSubsystem);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
trapArmSubsystem.setSpeed(0);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return trapArmSubsystem.getOuterSwitch();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.TrapArmCommands;

import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.robot.subsystems.TrapArmSubsystem;

public class setSpeedCommand extends InstantCommand {
private final TrapArmSubsystem trapArmSubsystem= TrapArmSubsystem.getInstance();
double speed;
/** Creates a new setSpeedCommand. */
public setSpeedCommand(double speed) {
addRequirements(trapArmSubsystem);
this.speed = speed;
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
trapArmSubsystem.setSpeed(speed);
}
}
56 changes: 56 additions & 0 deletions src/main/java/frc/robot/subsystems/TrapArmSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.subsystems;

import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import static frc.robot.Constants.TrapArmConstants.*;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class TrapArmSubsystem extends SubsystemBase {
private TalonSRX m_TrapMotor;
DigitalInput innerSwitch;
DigitalInput outerSwitch;

private static TrapArmSubsystem instance;

public static TrapArmSubsystem getInstance() {
if (instance == null) {
instance = new TrapArmSubsystem();
}
return instance;
}

/** Creates a new TrapArmSubsystem. */
private TrapArmSubsystem() {
this.m_TrapMotor = new TalonSRX(ArmMotorID);
this.innerSwitch = new DigitalInput(InnerSwitchID);
this.outerSwitch = new DigitalInput(OuterSwitchID);
}


public void setSpeed(double speed){
m_TrapMotor.set(ControlMode.PercentOutput,speed);
}


public boolean getInnerSwitch(){
return innerSwitch.get();
}


public boolean getOuterSwitch(){
return outerSwitch.get();
}



@Override
public void periodic() {
// This method will be called once per scheduler run
}
}