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

Merge Limelight, Some Auto & Climber to MAIN #16

Open
wants to merge 18 commits into
base: main
Choose a base branch
from
Open

Merge Limelight, Some Auto & Climber to MAIN #16

wants to merge 18 commits into from

Conversation

1ceit
Copy link
Member

@1ceit 1ceit commented Mar 6, 2024

No description provided.

@1ceit 1ceit requested review from MyaTaheri and BenBerol and removed request for BenBerol March 7, 2024 13:35
speedRotController = new PIDController(0.05, 0.002, 0);
speedRotController.enableContinuousInput(-180, 180);

addRequirements(swerveDrive, limelight);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think you should require limelight. You don't actually care if two commands that use limelight are running at the same time (and in fact may want that if you want to drive and aim your shooter at the same time)

public void climb(double speed) {
leftMotor.set(speed);
leftMotor.set(-speed);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

leftMotor.setInverted(true)

Comment on lines +19 to +20
new RunCommand(() -> this.climberSubsystem.climb(0.25), this.climberSubsystem).withTimeout(1.5),
new RunCommand(() -> this.climberSubsystem.climb(-0.25), this.climberSubsystem).withTimeout(0.5)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are your climb motors neos? You could use the encoder position that is built in to know if the climber is up, rather than relying on time.

public void climb(double speed) {
leftMotor.set(speed);
double speed1 = speed + 0.1;
leftMotor.set(-speed1);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

leftMotor.setInverted(true)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants