generated from DeepBlueRobotics/EmptyProject2024
-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge branch 'limelight' into bangbot
- Loading branch information
Showing
9 changed files
with
304 additions
and
79 deletions.
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
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
70 changes: 70 additions & 0 deletions
70
src/main/java/org/carlmontrobotics/commands/AutoMATICALLYGetNote.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,70 @@ | ||
// 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 org.carlmontrobotics.commands; | ||
|
||
import static org.carlmontrobotics.Constants.Limelightc.*; | ||
|
||
import org.carlmontrobotics.Constants.*; | ||
import org.carlmontrobotics.subsystems.*; | ||
|
||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.math.util.Units; | ||
import edu.wpi.first.wpilibj.Timer; | ||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||
import edu.wpi.first.wpilibj2.command.Command; | ||
import edu.wpi.first.wpilibj2.command.InstantCommand; | ||
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; | ||
import edu.wpi.first.wpilibj2.command.ParallelRaceGroup; | ||
import edu.wpi.first.wpilibj2.command.ProxyCommand; | ||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; | ||
import edu.wpi.first.wpilibj2.command.WaitCommand; | ||
|
||
public class AutoMATICALLYGetNote extends Command { | ||
/** Creates a new AutoMATICALLYGetNote. */ | ||
private Drivetrain dt; | ||
//private IntakeShooter effector; | ||
private Limelight ll; | ||
private Timer timer = new Timer(); | ||
|
||
public AutoMATICALLYGetNote(Drivetrain dt, Limelight ll /*IntakeShooter effector*/) { | ||
addRequirements(this.dt = dt); | ||
addRequirements(this.ll = ll); | ||
//addRequirements(this.effector = effector); | ||
// Use addRequirements() here to declare subsystem dependencies. | ||
} | ||
|
||
@Override | ||
public void initialize() { | ||
timer.reset(); | ||
timer.start(); | ||
//new Intake().finallyDo(()->{this.end(false);}); | ||
SmartDashboard.putBoolean("end", false); | ||
dt.setFieldOriented(false); | ||
} | ||
|
||
@Override | ||
public void execute() { | ||
double angleErrRad = Units.degreesToRadians(LimelightHelpers.getTX(Limelightc.INTAKE_LL_NAME)); | ||
double forwardDistErrMeters = ll.getDistanceToNote(); | ||
double strafeDistErrMeters = forwardDistErrMeters * Math.tan(angleErrRad); | ||
// dt.drive(0,0,0); | ||
dt.drive(Math.max(forwardDistErrMeters*2, MIN_MOVEMENT_METERSPSEC), Math.max(strafeDistErrMeters*2, MIN_MOVEMENT_METERSPSEC), Math.max(angleErrRad*2,MIN_MOVEMENT_RADSPSEC)); | ||
//180deg is about 6.2 rad/sec, min is .5rad/sec | ||
} | ||
|
||
// Called once the command ends or is interrupted. | ||
@Override | ||
public void end(boolean interrupted) { | ||
dt.setFieldOriented(true); | ||
SmartDashboard.putBoolean("end", true); | ||
} | ||
|
||
// Returns true when the command should end. | ||
@Override | ||
public boolean isFinished() { | ||
return false; | ||
//return timer.get() >= 0.5; | ||
} | ||
} |
61 changes: 61 additions & 0 deletions
61
src/main/java/org/carlmontrobotics/commands/MoveToNote.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,61 @@ | ||
// 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 org.carlmontrobotics.commands; | ||
|
||
import org.carlmontrobotics.Constants.Limelightc; | ||
import org.carlmontrobotics.subsystems.Drivetrain; | ||
import org.carlmontrobotics.subsystems.Limelight; | ||
import org.carlmontrobotics.subsystems.LimelightHelpers; | ||
|
||
import edu.wpi.first.math.util.Units; | ||
import edu.wpi.first.wpilibj.Timer; | ||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||
import edu.wpi.first.wpilibj2.command.Command; | ||
|
||
public class MoveToNote extends Command { | ||
private final Drivetrain dt; | ||
private final Limelight ll; | ||
private Timer timer = new Timer(); | ||
/** Creates a new MoveToNote. */ | ||
public MoveToNote(Drivetrain dt, Limelight ll) { | ||
// Use addRequirements() here to declare subsystem dependencies. | ||
addRequirements(this.dt=dt); | ||
addRequirements(this.ll=ll); | ||
} | ||
|
||
// Called when the command is initially scheduled. | ||
@Override | ||
public void initialize() { | ||
new AlignToNote(dt); | ||
timer.reset(); | ||
timer.start(); | ||
//new Intake().finallyDo(()->{this.end(false);}); | ||
SmartDashboard.putBoolean("end", false); | ||
dt.setFieldOriented(false); | ||
} | ||
|
||
// Called every time the scheduler runs while the command is scheduled. | ||
@Override | ||
public void execute() { | ||
double radErr = Units.degreesToRadians(LimelightHelpers.getTX(Limelightc.INTAKE_LL_NAME)); | ||
double distErr = ll.getDistanceToNote(); //meters | ||
double forwardErr = distErr * Math.cos(radErr); | ||
// dt.drive(0,0,0); | ||
dt.drive(Math.max(forwardErr*2, .5), 0, 0); | ||
//180deg is about 6.2 rad/sec, min is .5rad/sec | ||
} | ||
|
||
// Called once the command ends or is interrupted. | ||
@Override | ||
public void end(boolean interrupted) { | ||
dt.setFieldOriented(true); | ||
} | ||
|
||
// Returns true when the command should end. | ||
@Override | ||
public boolean isFinished() { | ||
return timer.get() >= 0.5; | ||
} | ||
} |
Oops, something went wrong.