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

Remove limitswitch #4

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
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
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,6 @@ public void disabledPeriodic() {}
@Override
public void autonomousInit() {
CommandScheduler.getInstance().cancelAll();
CommandScheduler.getInstance().schedule(m_robotContainer.zeroCommand());
}

/** This function is called periodically during autonomous. */
Expand All @@ -72,7 +71,9 @@ public void teleopInit() {
// this line or comment it out.
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();

}
CommandScheduler.getInstance().schedule(m_robotContainer.zeroEncoders());
}

/** This function is called periodically during operator control. */
Expand Down
15 changes: 7 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,21 +5,18 @@
package frc.robot;

import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.POVButton;
import edu.wpi.first.wpilibj.Joystick;
import frc.robot.commands.extensionarm.*;
import frc.robot.commands.manipulator.IntakeCone;
import frc.robot.commands.manipulator.IntakeCube;
import frc.robot.commands.manipulator.OuttakeCone;
import frc.robot.commands.manipulator.OuttakeCube;
import frc.robot.commands.extensionarm.DumbExtend;
import frc.robot.commands.extensionarm.DumbRetract;
import frc.robot.commands.extensionarm.BaseExtension;
import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.commands.*;
import frc.robot.commands.extensionarm.AutoZeroExtensionArm;
import frc.robot.commands.extensionarm.ExtensionExtend;
import frc.robot.commands.framework.Autos;
import frc.robot.subsystems.Chassis;
import frc.robot.subsystems.ExampleSubsystem;
Expand Down Expand Up @@ -76,7 +73,6 @@ public Manipulator getManipulator() {
*/
private void configureBindings() {

new JoystickButton(m_WeaponsGamepad, 1).whileTrue(new AutoZeroExtensionArm(m_extension));
new POVButton(m_weaponsGamepad, Constants.XBOXButtons.LST_POV_N).whileTrue(new DumbExtend(m_extension, this));
new POVButton(m_weaponsGamepad, Constants.XBOXButtons.LST_POV_S).whileTrue(new DumbRetract(m_extension, this));
new JoystickButton(m_weaponsGamepad, 3).whileTrue(new IntakeCone(getManipulator()));
Expand All @@ -88,8 +84,11 @@ private void configureBindings() {
/**
* Schedules a command to zero the extension arm
*/
public CommandBase zeroCommand() {
return (new AutoZeroExtensionArm(m_extension));
public CommandBase zeroEncoders() {
return (new ZeroEncoders(m_extension));
}
public CommandBase zeroEncoders() {
return (new ZeroEncoders(m_extension));
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,7 @@ public BaseExtension(ExtensionArm subsystem, RobotContainer container) {

// Called when the command is initially scheduled.
@Override
public void initialize() {
if(m_ExtensionArm.LimitSwitch()){ // if limit switch is hit, then zero encoders
m_ExtensionArm.resetEncoders();
m_ExtensionArm.setZeroed();
}
}
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,7 @@ public ExtensionExtend(ExtensionArm subsystem, RobotContainer container) {

// Called when the command is initially scheduled.
@Override
public void initialize() {
if(m_ExtensionArm.LimitSwitch()){
m_ExtensionArm.resetEncoders();
m_ExtensionArm.setZeroed();
}
}
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,50 +5,39 @@
package frc.robot.commands.extensionarm;

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.RobotContainer;
import frc.robot.subsystems.ExtensionArm;

/** An example command that uses an example subsystem. */
public class AutoZeroExtensionArm extends CommandBase {
public class ZeroEncoders extends CommandBase {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final ExtensionArm m_extensionArm;

/**
* Creates a new ExampleCommand.
*
* @param subsystem The subsystem used by this command.
*/
public AutoZeroExtensionArm(ExtensionArm subsystem) {
m_extensionArm = subsystem;
// Use addRequirements() here to declare subsystem dependencies.
private final ExtensionArm m_ExtensionArm;

public ZeroEncoders(ExtensionArm subsystem) {
m_ExtensionArm = subsystem;
addRequirements(subsystem);
}

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

m_ExtensionArm.resetEncoders();
m_ExtensionArm.setZeroed();
}

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

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_extensionArm.stop();
if (!interrupted) {
m_extensionArm.resetEncoders();
}
m_extensionArm.setZeroed();
}
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return m_extensionArm.LimitSwitch();
return false;
}

}


13 changes: 2 additions & 11 deletions src/main/java/frc/robot/subsystems/ExtensionArm.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,7 @@ public class ExtensionArm extends SubsystemBase {
private final WPI_TalonSRX m_rightMotor;

private final MotorControllerGroup m_extensionMotors;

private final DigitalInput m_limitSwitch;
private boolean isZeroed = false;
private boolean isZeroed = true;
/**Extension arm testing constants*/
public static double maxExtensionTicks = 100; // TODO
public static double kExtensionDeadband = 0.05; //The % of max extension where it will slow down (works on both ends)
Expand All @@ -42,8 +40,6 @@ public ExtensionArm() {
m_leftMotor.configSelectedFeedbackSensor(FeedbackDevice.QuadEncoder);
m_rightMotor.configSelectedFeedbackSensor(FeedbackDevice.QuadEncoder);

m_limitSwitch = new DigitalInput(CAN.limitSwitch);

m_rightMotor.configFactoryDefault();
m_leftMotor.configFactoryDefault();

Expand All @@ -63,10 +59,6 @@ public ExtensionArm() {
}

/**returns if the limit switch has been hit*/
public boolean LimitSwitch(){
return m_limitSwitch.get();
}

public double getPosition(){
return m_leftMotor.getSelectedSensorPosition() * extensionTicksToArmDistance;
}
Expand Down Expand Up @@ -154,7 +146,7 @@ public double rawMotorSpeed(double y) {
}

public boolean allowedToMovePastEnds(double y) {
if (LimitSwitch() && (y <= 0)) { // if trying to move past the limit switch, return false
if ((getPosition() <= 0) && (y <= 0)) { // if trying to move past the limit switch, return false
return false;
} else if ((getPosition() >= maxExtensionTicks) && (y >= 0)) { // if trying to move past maxTicks, return false
return false;
Expand Down Expand Up @@ -218,7 +210,6 @@ public double getPercentage() {
public void initSendable(SendableBuilder builder){
builder.addDoubleProperty("Position", this::getPosition, null);
builder.addDoubleProperty("Dumb Speed", this::getDumbSpeed, this::setDumbSpeed);
builder.addBooleanProperty("Hit Limit Switch", this::LimitSwitch, null);
builder.addDoubleProperty("CMax Extension Ticks", this::getMaxExtensionTicks, this::setMaxExtensionTicks);
builder.addDoubleProperty("CExtension Deadband", this::getkExtensionDeadband, this::setkExtensionDeadband);
builder.addDoubleProperty("CSlow Zone Extension Percentage", this::getPercentage, this::setSlowExtensionEndsDistance);
Expand Down