-
Notifications
You must be signed in to change notification settings - Fork 4
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
Code for claw mech. RobotContainer updated with button bindings and s… #10
+258
−7
Closed
Changes from 8 commits
Commits
Show all changes
9 commits
Select commit
Hold shift + click to select a range
755dfcb
Code for claw mech. RobotContainer updated with button bindings and s…
Ippyb ee88ee8
per 7 claw mech with states, button release, and encoders
Ippyb ed326f2
initialized booleans
Ippyb 9fec24f
add 2nd motor
PinkBlueSky 046efc6
Removed duplicate Xbox
PinkBlueSky 21e07ec
Use only one encoder; add back the 2nd xbox controller
PinkBlueSky 34c2f1b
Edit controller bindings and restructure close/lift command
PinkBlueSky b608226
Restructure ClawSubsystem to have state vars; add new commands
PinkBlueSky f16d99c
Print encoder positions for the claw
PinkBlueSky File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
39 changes: 39 additions & 0 deletions
39
src/main/java/frc/robot/commands/claw/CloseClawCommand.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,39 @@ | ||
package frc.robot.commands.claw; | ||
|
||
import edu.wpi.first.wpilibj2.command.CommandBase; | ||
import frc.robot.subsystems.claw.ClawSubsystem; | ||
|
||
public class CloseClawCommand extends CommandBase { | ||
@SuppressWarnings({ "PMD.UnusedPrivateField", "PMD.SingularField" }) | ||
|
||
private final ClawSubsystem clawSubsystem; | ||
|
||
public CloseClawCommand(ClawSubsystem clawSubsystem) { | ||
this.clawSubsystem = clawSubsystem; | ||
|
||
addRequirements(clawSubsystem); | ||
} | ||
|
||
@Override | ||
public void initialize() { | ||
} | ||
|
||
@Override | ||
public void execute() { | ||
// Set motor powers to close the claw | ||
clawSubsystem.setClosePowers(); | ||
} | ||
|
||
@Override | ||
public boolean isFinished() { | ||
// If both motors are stalled, command is finished | ||
return clawSubsystem.areBothMotorsStalled(); | ||
} | ||
|
||
@Override | ||
public void end(boolean interrupted) { | ||
// Stop motors | ||
clawSubsystem.setNeutralPowers(); | ||
} | ||
|
||
} |
42 changes: 42 additions & 0 deletions
42
src/main/java/frc/robot/commands/claw/OpenClawCommand.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,42 @@ | ||
package frc.robot.commands.claw; | ||
|
||
import edu.wpi.first.wpilibj2.command.CommandBase; | ||
import edu.wpi.first.wpilibj2.command.button.JoystickButton; | ||
import frc.robot.subsystems.claw.ClawSubsystem; | ||
|
||
public class OpenClawCommand extends CommandBase { | ||
@SuppressWarnings({ "PMD.UnusedPrivateField", "PMD.SingularField" }) | ||
|
||
private final ClawSubsystem clawSubsystem; | ||
private JoystickButton button; | ||
|
||
public OpenClawCommand(ClawSubsystem clawSubsystem, JoystickButton button) { | ||
this.clawSubsystem = clawSubsystem; | ||
this.button = button; | ||
|
||
addRequirements(clawSubsystem); | ||
} | ||
|
||
@Override | ||
public void initialize() { | ||
} | ||
|
||
@Override | ||
public void execute() { | ||
// Set motor powers to open the claw | ||
clawSubsystem.setOpenPowers(); | ||
} | ||
|
||
@Override | ||
public boolean isFinished() { | ||
// If button is still pressed, the command is not finished | ||
return !button.get(); | ||
} | ||
|
||
@Override | ||
public void end(boolean interrupted) { | ||
// Stop motors | ||
clawSubsystem.setNeutralPowers(); | ||
} | ||
|
||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
131 changes: 131 additions & 0 deletions
131
src/main/java/frc/robot/subsystems/claw/ClawSubsystem.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,131 @@ | ||
package frc.robot.subsystems.claw; | ||
|
||
import edu.wpi.first.wpilibj2.command.CommandScheduler; | ||
import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
|
||
import com.ctre.phoenix.motorcontrol.can.TalonSRX; | ||
import edu.wpi.first.wpilibj.Solenoid; | ||
|
||
import com.ctre.phoenix.motorcontrol.ControlMode; | ||
import com.ctre.phoenix.motorcontrol.FeedbackDevice; | ||
|
||
import static frc.robot.Constants.ClawConstants.*; | ||
|
||
public class ClawSubsystem extends SubsystemBase { | ||
private TalonSRX rightMotor; | ||
private TalonSRX leftMotor; | ||
private Solenoid pfft; | ||
|
||
// Position variables for the motors | ||
private double rightPos; | ||
private double leftPos; | ||
|
||
// Right and left motor powers -- state variables | ||
private double rightMotorPower; | ||
private double leftMotorPower; | ||
|
||
// State variable for whether the pneumatic is lifted or not | ||
private boolean liftClaw; | ||
|
||
public ClawSubsystem() { | ||
CommandScheduler.getInstance().registerSubsystem(this); | ||
|
||
// Initialize motors and pneumatic | ||
rightMotor = new TalonSRX(rightMotorPort); | ||
leftMotor = new TalonSRX(leftMotorPort); | ||
|
||
pfft = new Solenoid(pfftPCMPort); | ||
|
||
// Configure the motors for the encoders | ||
rightMotor.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, 0, 0); | ||
rightMotor.setSelectedSensorPosition(0); | ||
|
||
leftMotor.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, 0, 0); | ||
leftMotor.setSelectedSensorPosition(0); | ||
|
||
// Set initial motor position vars (for checking if motors are stalled) | ||
rightPos = 0; | ||
leftPos = 0; | ||
|
||
liftClaw = false; | ||
|
||
} | ||
|
||
@Override | ||
public void periodic() { | ||
|
||
// Set motor powers | ||
rightMotor.set(ControlMode.PercentOutput, rightMotorPower); | ||
leftMotor.set(ControlMode.PercentOutput, leftMotorPower); | ||
|
||
// Set pneumatic | ||
pfft.set(liftClaw); | ||
} | ||
|
||
/** | ||
* Set motor powers to open. | ||
*/ | ||
public void setOpenPowers() { | ||
rightMotorPower = rightOpenPower; | ||
leftMotorPower = leftOpenPower; | ||
} | ||
|
||
/** | ||
* Set motor powers to close. | ||
*/ | ||
public void setClosePowers() { | ||
rightMotorPower = -rightOpenPower; | ||
leftMotorPower = -leftOpenPower; | ||
} | ||
|
||
/** | ||
* Set motor powers to zero. | ||
*/ | ||
public void setNeutralPowers() { | ||
rightMotorPower = 0; | ||
leftMotorPower = 0; | ||
} | ||
|
||
public boolean getClawLift() { | ||
return liftClaw; | ||
} | ||
|
||
public void setClawLift(boolean liftClaw) { | ||
this.liftClaw = liftClaw; | ||
} | ||
|
||
/** | ||
* Checks if the claw motors are not moving (ie. if change in position is less | ||
* than a small delta value). | ||
* | ||
* @return true if stalled; false if moving | ||
*/ | ||
public boolean isMotorStalled(boolean right) { | ||
double newRightPos = rightMotor.getSelectedSensorPosition(); | ||
double newLeftPos = leftMotor.getSelectedSensorPosition(); | ||
|
||
// If motors are barely changing position | ||
boolean isRightStalled = Math.abs(newRightPos - rightPos) <= stallDelta; | ||
boolean isLeftStalled = Math.abs(newLeftPos - leftPos) <= stallDelta; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. this will probably work; for more robust code it might make sense to normalize vs time |
||
|
||
// Save new motor positions | ||
rightPos = newRightPos; | ||
leftPos = newLeftPos; | ||
|
||
return right ? isRightStalled : isLeftStalled; | ||
} | ||
|
||
/** | ||
* Returns true if both motors are stalled. | ||
* | ||
* @return true if both are stalled | ||
*/ | ||
public boolean areBothMotorsStalled() { | ||
return isMotorStalled(true) && isMotorStalled(false); | ||
} | ||
|
||
@Override | ||
public void simulationPeriodic() { | ||
// This method will be called once per scheduler run during simulation | ||
} | ||
} |
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
how it makes more sense to me is a boolean clawOpen, and then handle stalling logic / powers inside each periodic loop.. for one, it abstracts what should be abstracted in my opinion (I can't imagine anyone, including autonomous, needing something besides open + closed for claw control). that means the commands would just toggle this boolean, and then in periodic we take the boolean, and see which way to power the motors. If the motors are stalling, then we stop powering them.
this also adds the benefit of not running into a scenario where having multiple claw commands 'consumes' the change in position of the encoders, making the stall return true. Essentially what I'm saying is that this logic (for when to move the motors to get to the desired position) should only happen in the subsystem anyways, cuz it's at the subsystem's level of abstraction... idk if that makes sense?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Hmm... maybe...
Part of the reason why the code is structured like this is because we discussed last class and decided to have a button "press and hold" control the opening of the claw. So in that sense it seemed more logical to me to create a command that handles that instead of the subsystem. Because then, the subsystem would need more than just one boolean clawOpen to control the claw opening... otherwise there's no way to implement the button hold --> open claw thing.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
For the second point about consuming the position of encoders.. what exactly does that mean? Like if two commands were trying to figure out if the motors are stalling? Also according to the docs, I believe only one command of a given subsystem can be run at a time. So there should never be any conflicts... idk I might have it totally wrong