Skip to content

Commit

Permalink
Merge branch 'main' of https://github.com/primo4586/RobotCode2024 int…
Browse files Browse the repository at this point in the history
…o PreperForShooting

# Conflicts:
#	src/main/java/frc/robot/Constants.java
  • Loading branch information
ori-coval committed Jan 22, 2024
2 parents 1ffd6de + 4b11ee5 commit be10b8a
Show file tree
Hide file tree
Showing 11 changed files with 259 additions and 22 deletions.
14 changes: 12 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -308,16 +308,26 @@ public static class ShooterConstants {
.put(2.1, 10.2);

}
public static class CollectingConstants{
public static class IntakeConstants{
public static final int SwitchID=1;
public static final int CollectingMotorID=10;
public static final int IntakeMotorID=10;
public static final double getNoteSpeed = 0.0;
public static final double GroundIntakePose = 0.0;
}
public static class FeederConstants{

public static final int FeederShootSpeed = 20;
public static final int FeederMotorId = 3;
public static final int SwitchID = 0;
public static final double FeederMotorSpeed = 0.8;
public static final double getNoteSpeed = 0;

}

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,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.IntakeCommands;

import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import frc.robot.Constants.IntakeConstants;
import frc.robot.commands.IntakeArmCommands.MoveIntakeArmToDegree;
import frc.robot.commands.feederCommands.FeedUntilNote;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class CollectToFeeder extends ParallelCommandGroup {
/** Creates a new MoveIntakeToCollectNote. */
public CollectToFeeder() {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());
addCommands(
new IntakeSetSpeed(IntakeConstants.getNoteSpeed),
new FeedUntilNote(),
new MoveIntakeArmToDegree(IntakeConstants.GroundIntakePose));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,16 @@
// 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.CollectingCommands;
package frc.robot.commands.IntakeCommands;

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

public class setSpeedUntilFeedCommand extends Command {
private final CollectingSubsystem collectingSubsystem = CollectingSubsystem.getInstance();
public class InatkeUntilNote extends Command {
private final IntakeSubsystem collectingSubsystem = IntakeSubsystem.getInstance();
double speed;
/** Creates a new setSpeedUntilFeedCommand. */
public setSpeedUntilFeedCommand(double speed) {
public InatkeUntilNote(double speed) {
addRequirements(collectingSubsystem);
this.speed=speed;
// Use addRequirements() here to declare subsystem dependencies.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,19 @@
// 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.CollectingCommands;
package frc.robot.commands.IntakeCommands;

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

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class setSpeedCommand extends InstantCommand {
private final CollectingSubsystem collectingSubsystem = CollectingSubsystem.getInstance();
public class IntakeSetSpeed extends InstantCommand {
private final IntakeSubsystem collectingSubsystem = IntakeSubsystem.getInstance();
double speed;
/** Creates a new setSpeedCommand. */
public setSpeedCommand(double speed) {
public IntakeSetSpeed(double speed) {
addRequirements(collectingSubsystem);
this.speed = speed;
// Use addRequirements() here to declare subsystem dependencies.
Expand Down
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);
}
}
39 changes: 39 additions & 0 deletions src/main/java/frc/robot/commands/feederCommands/FeedUntilNote.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
// 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.feederCommands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.FeederConstants;
import frc.robot.subsystems.FeederSubsystem;

public class FeedUntilNote extends Command {
private final FeederSubsystem feederSubsystem = FeederSubsystem.getInstance();
/** Creates a new FeedUntilNote. */
public FeedUntilNote() {
addRequirements(feederSubsystem);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
feederSubsystem.setSpeed(FeederConstants.getNoteSpeed);}

// 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) {
feederSubsystem.setSpeed(0);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return feederSubsystem.getSwitch();
}
}
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/subsystems/FeederSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@

import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;

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

import static frc.robot.Constants.FeederConstants.*;
Expand All @@ -15,10 +17,12 @@ public class FeederSubsystem extends SubsystemBase {

//the feeder's motor
TalonSRX m_Feeder;
DigitalInput lazerSensor;

//constructor
private FeederSubsystem(){
m_Feeder = new TalonSRX(FeederMotorId);
this.lazerSensor = new DigitalInput(SwitchID);
}

// singelton
Expand All @@ -36,6 +40,10 @@ public void setSpeed(double motorSpeed){
m_Feeder.set(ControlMode.PercentOutput, motorSpeed);
}

public boolean getSwitch(){
return lazerSensor.get();
}

@Override
public void periodic() {
// This method will be called once per scheduler run
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,29 +9,29 @@
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

import static frc.robot.Constants.CollectingConstants.*;
import static frc.robot.Constants.IntakeConstants.*;

public class CollectingSubsystem extends SubsystemBase {
private TalonSRX m_collecting;
public class IntakeSubsystem extends SubsystemBase {
private TalonSRX m_Intake;
DigitalInput lazerSensor;

private static CollectingSubsystem instance;
private static IntakeSubsystem instance;

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

/** Creates a new CollectingSubsystem. */
public CollectingSubsystem() {
this.m_collecting = new TalonSRX(CollectingMotorID);
/** Creates a new IntakeSubsystem. */
private IntakeSubsystem() {
this.m_Intake = new TalonSRX(IntakeMotorID);
this.lazerSensor = new DigitalInput(SwitchID);
}

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

public boolean getSwitch(){
Expand Down
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
}
}

0 comments on commit be10b8a

Please sign in to comment.