-
Notifications
You must be signed in to change notification settings - Fork 2
Drive with Time command complete #121
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
Open
IshanBaliyan
wants to merge
16
commits into
master
Choose a base branch
from
IshanDistanceAuto
base: master
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from 12 commits
Commits
Show all changes
16 commits
Select commit
Hold shift + click to select a range
2840727
Drive with Time command complete
IshanBaliyan 3dfc4c0
Added driving backwards distance functionality
IshanBaliyan bdc6586
Added some features to Drive with Distance
IshanBaliyan fbe749b
Fixed not moving bug errors
IshanBaliyan 760954b
Resolved some changes for reviewed code
IshanBaliyan 10fdcdd
Merge branch 'master' into IshanDistanceAuto
IshanBaliyan f742bb6
Merge branch 'master' into IshanDistanceAuto
IshanBaliyan ce71138
Rebasing changes onto drive with distance
IshanBaliyan db7f344
Merge branch 'master' into IshanDistanceAuto
IshanBaliyan 7493954
Merge remote-tracking branch 'origin/IshanDistanceAuto' into IshanDis…
IshanBaliyan f40e40b
Pair programming Ishan and George, Power team
georgetzavelas b34f7b3
Quick fix on import statements
IshanBaliyan 2753d62
Merge branch 'master' into IshanDistanceAuto
IshanBaliyan 4c4928d
Quick fix for typo
IshanBaliyan 0d4a03a
Merge branch 'master' into IshanDistanceAuto
IshanBaliyan 3bffc9a
Quick fix in syntax
IshanBaliyan 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 hidden or 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
196 changes: 196 additions & 0 deletions
196
src/main/java/frc/robot/commands/DriveWithDistance.java
This file contains hidden or 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,196 @@ | ||
| /*----------------------------------------------------------------------------*/ | ||
| /* Copyright (c) 2019 FIRST. All Rights Reserved. */ | ||
| /* Open Source Software - may be modified and shared by FRC teams. The code */ | ||
| /* must be accompanied by the FIRST BSD license file in the root directory of */ | ||
| /* the project. */ | ||
| /*----------------------------------------------------------------------------*/ | ||
|
|
||
| package frc.robot.commands; | ||
|
|
||
| import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||
| import edu.wpi.first.wpilibj2.command.CommandBase; | ||
| import frc.robot.subsystems.DriveBase; | ||
| import frc.robot.subsystems.DriveBaseHolder; | ||
| import frc.robot.subsystems.DriveBase.DistanceType; | ||
|
|
||
| public class DriveWithDistance extends CommandBase { | ||
|
|
||
| //Initializing private version of drivebase object | ||
| private final DriveBase driveBase; | ||
|
|
||
| //The speed that the robot must move below to move backwards | ||
| private final static double ZERO_SPEED = 0; | ||
|
|
||
| private final static double DEFAULT_RIGHT_SPEED = 0.5; | ||
| private final static double DEFAULT_LEFT_SPEED = 0.5; | ||
|
|
||
| // initialization of the variables | ||
| public double desiredLeftDistance = 0; | ||
| public double desiredRightDistance = 0; | ||
| public double desiredRightEncoderTicks, desiredLeftEncoderTicks; | ||
| public double leftSpeed = 0; | ||
| public double rightSpeed = 0; | ||
| public DistanceType distanceType; | ||
| public double currentConversion; | ||
| public boolean commandFinished = false; | ||
|
|
||
| /** | ||
| * Constructor to be used when the input specifications do not provide the right and left speed (assumed to be 0.5) | ||
| * | ||
| * @param distance The distance to drive | ||
| * @param distanceType The distance unit type to drive in | ||
| */ | ||
|
|
||
| public DriveWithDistance(double distance, DistanceType distanceType) { | ||
| this(distance, distanceType, DEFAULT_RIGHT_SPEED, DEFAULT_LEFT_SPEED); | ||
| } | ||
|
|
||
| /** | ||
| * Constructor to be used when the input gives the right and left speed | ||
| * | ||
| * @param distance The distance to drive | ||
| * @param distanceType The distance unit type to drive in | ||
| * @param rightSpeed The right motor speed | ||
| * @param leftSpeed The left motor speed | ||
| */ | ||
| public DriveWithDistance(double distance, DistanceType distanceType, double rightSpeed, double leftSpeed) { | ||
| this(distance, distance, distanceType, rightSpeed, leftSpeed); | ||
| } | ||
|
|
||
|
|
||
| /** | ||
| * Constructor to be used when the input gives the right and left distance | ||
| * | ||
| * @param rightDistance The distance to drive for right motor | ||
| * @param leftDistance The distance to drive for left motor | ||
| * @param distanceType The distance unit type to drive in | ||
| * @param rightSpeed The right motor speed | ||
| * @param leftSpeed The left motor speed | ||
| */ | ||
| public DriveWithDistance(double rightDistance, double leftDistance, DistanceType distanceType, double rightSpeed, double leftSpeed) { | ||
| //Initating drivebase | ||
| this.driveBase = DriveBaseHolder.getInstance(); | ||
|
|
||
| //Setting current distance unit | ||
| this.distanceType = distanceType; | ||
|
|
||
| addRequirements(driveBase); | ||
|
|
||
| assignDistanceType(distanceType); | ||
|
|
||
| //Setting the right speed and left speed according to input specifications | ||
| this.rightSpeed = rightSpeed; | ||
| this.leftSpeed = leftSpeed; | ||
|
|
||
| //Determing the amount of desired encoder ticks to drive by getting the distnace and multiplying by the chosen distance unit | ||
| this.desiredRightEncoderTicks = rightDistance * this.currentConversion; | ||
| this.desiredLeftEncoderTicks = leftDistance * this.currentConversion; | ||
|
|
||
| } | ||
|
|
||
| /** | ||
| * Assigns the current conversion from encoder ticks to distance type | ||
| * | ||
| * @param distanceType The distance unit that the robot is using for driving | ||
| */ | ||
| private void assignDistanceType(DistanceType distanceType) { | ||
| //Setting the current conversion type according to the chosen distance unit | ||
| switch (distanceType) { | ||
| case FEET: | ||
| this.currentConversion = DriveBase.DistanceUnit.FEET.encoderTicks; | ||
|
|
||
| break; | ||
| case METERS: | ||
| this.currentConversion = DriveBase.DistanceUnit.METERS.encoderTicks; | ||
|
|
||
| break; | ||
| case CENTIMETERS: | ||
| this.currentConversion = DriveBase.DistanceUnit.CENTIMETERS.encoderTicks; | ||
|
|
||
| break; | ||
| case INCHES: | ||
| this.currentConversion = DriveBase.DistanceUnit.INCHES.encoderTicks; | ||
|
|
||
| break; | ||
|
|
||
| //Default is meters | ||
| default: | ||
|
|
||
| this.currentConversion = DriveBase.DistanceUnit.METERS.encoderTicks; | ||
| break; | ||
|
|
||
| } | ||
| } | ||
|
|
||
| /** | ||
| * Called one when the command is initially scheduled and determines the desired distance to travel | ||
| * | ||
| */ | ||
| @Override | ||
| public void initialize() { | ||
|
|
||
| //Add the desired amount of encoder ticks to the current distance to get the amount of encoder ticks that the robot needs to drive | ||
| desiredRightDistance = driveBase.getRightDistance() + desiredRightEncoderTicks; | ||
| desiredLeftDistance = driveBase.getLeftDistance() + desiredLeftEncoderTicks; | ||
|
|
||
| addRequirements(DriveBaseHolder.getInstance()); | ||
| } | ||
|
|
||
| /** | ||
| * Called every time the scheduler runs while the command is scheduled. (run every 20ms) and determines the current distance | ||
| * | ||
| */ | ||
| @Override | ||
| public void execute() { | ||
|
|
||
| //Get the current distance of the right encoder and store value in variable | ||
| double currentRightDistance = DriveBaseHolder.getInstance().getRightDistance(); | ||
| double currentLeftDistance = DriveBaseHolder.getInstance().getLeftDistance(); | ||
|
|
||
| //Run motors according to output of the speeds | ||
| driveBase.tankDrive(leftSpeed, rightSpeed, false); | ||
|
|
||
| //Dashboard | ||
| SmartDashboard.putNumber("Left Speed", leftSpeed); | ||
| SmartDashboard.putNumber("Right Speed", rightSpeed); | ||
| SmartDashboard.putNumber("Left Error", desiredLeftDistance - currentLeftDistance); | ||
| SmartDashboard.putNumber("Right Error", desiredRightDistance - currentRightDistance); | ||
|
|
||
| //Code for figuring out when the robot is finished driving and handeling user input validation | ||
|
|
||
| // Update to the current right/left distance that the robot has driven | ||
| currentRightDistance = DriveBaseHolder.getInstance().getRightDistance(); | ||
| currentLeftDistance = DriveBaseHolder.getInstance().getLeftDistance(); | ||
|
|
||
| // If the robot has reached or surpassed the desired distance, then stop the | ||
| // robot. Otherwise, keep moving (moving forward OR moving backwards). | ||
| if (Math.abs(currentRightDistance) >= desiredRightDistance) { | ||
IshanBaliyan marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| rightSpeed = ZERO_SPEED; | ||
| } | ||
|
|
||
| // If the robot has reached or surpassed the desired distance, then stop the | ||
| // robot. Otherwise, keep moving (moving forward). | ||
| if (Math.abs(currentLeftDistance) >= desiredLeftDistance) { | ||
| leftSpeed = ZERO_SPEED; | ||
| } | ||
|
|
||
| //If the left and right speed are zero, just stop the robot | ||
| if ((leftSpeed == ZERO_SPEED && rightSpeed == ZERO_SPEED) || | ||
| (desiredLeftDistance >= currentLeftDistance && desiredRightDistance >= currentRightDistance)) { | ||
| commandFinished = true; | ||
| } | ||
|
|
||
| //Taking the changed left and right speed and adding their updated values to the drivebase | ||
| driveBase.tankDrive(leftSpeed, rightSpeed, false); | ||
| } | ||
|
|
||
| /** | ||
| * Determines when the command is finished using the current distnce and desired distance | ||
| * | ||
| */ | ||
|
|
||
| @Override | ||
| public boolean isFinished() { | ||
IshanBaliyan marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| return commandFinished; | ||
| } | ||
| } | ||
This file contains hidden or 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 hidden or 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
Oops, something went wrong.
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.
Uh oh!
There was an error while loading. Please reload this page.