Skip to content

Commit

Permalink
[#29] no auton working dum
Browse files Browse the repository at this point in the history
  • Loading branch information
HeroSoLos committed Feb 17, 2024
1 parent ff42641 commit 73a04a7
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 7 deletions.
12 changes: 9 additions & 3 deletions src/main/java/frc/robot/command/AlignToTag.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ public class AlignToTag extends Command {
private Limelights limelights;
private MoveToPose move;
private int limelightPrevPipeline = 0;

private boolean MoveToPoseDone;
private boolean aligning;
/** Creates a new AlignToTag. */
public AlignToTag(Pose2d target, Swerve drivetrain, SwerveRequest.FieldCentric drive, XboxController driver) {
Expand Down Expand Up @@ -78,14 +78,20 @@ public void execute() {
// .whileTrue(new MoveToPose(target, drivetrain, drive).schedule());
//new Trigger(() -> (new MoveToPose(target, drivetrain, drive).isFinished()))
// .whileTrue(AutoBuilder.followPath(path));
if (!(new MoveToPose(target, drivetrain, drive).isFinished())) {
MoveToPoseDone = Math.sqrt((target.getTranslation().getX() - drivetrain.getPose().get().getTranslation().getX())*(target.getTranslation().getX() - drivetrain.getPose().get().getTranslation().getX()) + (target.getTranslation().getY() - drivetrain.getPose().get().getTranslation().getY())*(target.getTranslation().getY() - drivetrain.getPose().get().getTranslation().getY()))<0.4;
System.out.println(Math.sqrt((target.getTranslation().getX() - drivetrain.getPose().get().getTranslation().getX())*(target.getTranslation().getX() - drivetrain.getPose().get().getTranslation().getX()) + (target.getTranslation().getY() - drivetrain.getPose().get().getTranslation().getY())*(target.getTranslation().getY() - drivetrain.getPose().get().getTranslation().getY()))<0.4);
System.out.println(new MoveToPose(target, drivetrain, drive).isFinished());
if (!aligning && !MoveToPoseDone/*(new MoveToPose(target, drivetrain, drive).isFinished())*/) {
System.out.println("AHASIDHASHASID");
move = new MoveToPose(target, drivetrain, drive);
move.initialize();
move.execute();
} else if (!aligning && (new MoveToPose(target, drivetrain, drive).isFinished()) ) {
} else if (!aligning) {
System.out.println("IM DONEWITHMOVETOPOSE AUTOBUILDING!!!!!!!!!!!!!!!!!!!!!!!!!!1*(!*)");
AutoBuilder.followPath(path);
aligning = true;
}else{
System.out.println("running path");
}

}
Expand Down
10 changes: 6 additions & 4 deletions src/main/java/frc/robot/command/MoveToPose.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@ public class MoveToPose extends Command {
private Pose2d current;
private double dx;
private double dy;
private final double kp = 0.3; //1.8 old
private final double minSpeed = 0.2; //0.9 old
private final double kp = 0.8; //1.8 old
private final double minSpeed = 0.4; //0.9 old
private double powerx;
private double powery;
/**
Expand Down Expand Up @@ -58,9 +58,11 @@ public void execute() {
LightningShuffleboard.setDouble("MoveToPose", "targetY", target.getY());

current = drivetrain.getPose().get();
System.out.println(current);
dx = target.getTranslation().getX() - current.getTranslation().getX();
dy = target.getTranslation().getY() - current.getTranslation().getY();

System.out.println(dx);
System.out.println(dy);
powerx = dx * kp;
powery = dy * kp;

Expand All @@ -81,7 +83,7 @@ public void execute() {
}

var dist = Math.sqrt(dx*dx + dy*dy);
if (dist < 0.3) {
if (dist < 0.4) {
powerx = 0;
powery = 0;
finished = true;
Expand Down

0 comments on commit 73a04a7

Please sign in to comment.