Skip to content

Commit

Permalink
Merge pull request #6 from MOERobotics/lehigh
Browse files Browse the repository at this point in the history
Lehigh
  • Loading branch information
mailmindlin authored Apr 8, 2024
2 parents acd1b18 + 51f91b0 commit 8a3fbb5
Show file tree
Hide file tree
Showing 26 changed files with 1,554 additions and 338 deletions.
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/AllianceFlip.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,4 +45,7 @@ public static List<Translation2d> apply(List<Translation2d>pts){
return pts.stream().map(AllianceFlip::apply).toList();
}

public static List<Pose2d> apply(ArrayList<Pose2d> pts) {
return pts.stream().map(AllianceFlip::apply).toList();
}
}
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

package frc.robot;

import edu.wpi.first.math.geometry.Rotation2d;

/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
* constants. This class should not be used for any other purpose. All constants should be declared
Expand All @@ -16,4 +18,6 @@ public final class Constants {
public static class OperatorConstants {
public static final int kDriverControllerPort = 0;
}
public static Rotation2d collectorShoulder = Rotation2d.fromDegrees(83.6);
public static Rotation2d collectorWrist = Rotation2d.fromDegrees(-45);
}
237 changes: 126 additions & 111 deletions src/main/java/frc/robot/FortissiMOEContainer.java

Large diffs are not rendered by default.

5 changes: 4 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,16 @@ public void robotInit() {
public void robotPeriodic() {
CommandScheduler.getInstance().run();
SmartDashboard.putData("running command", CommandScheduler.getInstance());
initRobotContainer(false);
}

@Override
public void disabledInit() {}

@Override
public void disabledPeriodic() {}
public void disabledPeriodic() {
if (m_robotContainer!= null) m_robotContainer.resetArmPos();
}

@Override
public void autonomousInit() {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/SwerveBotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ public class SwerveBotContainer {
driveP, driveI, driveD, driveFF
);
private final SwerveDrive swerveSubsystem = new SwerveDrive(frontLeftModule, backLeftModule, frontRightModule, backRightModule,
pigeon, maxMPS,maxMPSSquared, maxRPS, maxRPSSquared,1,0,0, 1.0, 0, 0,
pigeon, maxMPS, maxMPS,maxMPSSquared, maxRPS, maxRPSSquared,1,0,0, 1.0, 0, 0,
.04,0,0);
/////////////////////////////////////////////////////////////////////////////drive subsystems end

Expand Down
49 changes: 34 additions & 15 deletions src/main/java/frc/robot/commands/ArmPathFollow.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,15 @@
import frc.robot.subsystems.Arm;
import edu.wpi.first.wpilibj2.command.Command;

import static java.lang.Math.abs;

/** An example command that uses an example subsystem. */
public class ArmPathFollow extends Command {
private final Arm armSubsystem;
Translation2d desiredPoint;
Translation2d startPoint, currPos;
Timer timer;
double targetDist, speed, accel, s;
double targetDist, speed, accel, s, v_0;


public ArmPathFollow(Arm subsystem, Rotation2d shoulderPos, Rotation2d wristPos, double speed, double accel) {
Expand All @@ -34,40 +36,57 @@ public ArmPathFollow(Arm subsystem, Rotation2d shoulderPos, Rotation2d wristPos,

@Override
public void initialize() {
System.out.println("initialized");
SmartDashboard.putNumber("made it to init", timer.get());
startPoint = new Translation2d(armSubsystem.shoulderState().getDegrees(), armSubsystem.wristState().getDegrees());
targetDist = startPoint.getDistance(desiredPoint);
v_0 = armSubsystem.getArmSpeed();
timer.restart();
}

@Override
public void execute() {
//SmartDashboard.putNumber("made it", timer.get());
//s = LineHelpers.getS(targetDist, speed, accel, timer.get());
//SmartDashboard.putNumber("ArmPathFollow s", s);
s = Math.min(timer.get()*speed, startPoint.getDistance(desiredPoint));
//var interPos = startPoint.getDistance(desiredPoint)
//var interPos = startPoint.interpolate(desiredPoint, s / startPoint.getDistance(desiredPoint));
// double shoulderPos = LineHelpers.getPositionX(startPoint, desiredPoint, s);
// double wristPos = LineHelpers.getPositionY(startPoint, desiredPoint, s);
var shoulderPos = (desiredPoint.getX()-startPoint.getX())/startPoint.getDistance(desiredPoint)*s+startPoint.getX();
var wristPos = (desiredPoint.getY()-startPoint.getY())/startPoint.getDistance(desiredPoint)*s+startPoint.getY();

s = LineHelpers.getS(desiredPoint.getDistance(startPoint), speed, accel, v_0, timer.get());
double v = LineHelpers.getVel(desiredPoint.getDistance(startPoint), speed, accel, v_0, timer.get());
var shoulderPos = (desiredPoint.getX()-startPoint.getX())/desiredPoint.getDistance(startPoint)*s+startPoint.getX();

double wristPos = (desiredPoint.getY()-startPoint.getY())/(desiredPoint.getX()-startPoint.getX())*(armSubsystem.shoulderState().getDegrees()
- startPoint.getX()) + startPoint.getY();

double wristVel = (desiredPoint.getY()-startPoint.getY())/(desiredPoint.getDistance(startPoint))*v;
double shoulderVel = (desiredPoint.getX()-startPoint.getX())/(desiredPoint.getDistance(startPoint))*v;

if (Math.abs(desiredPoint.getX() - startPoint.getX()) <= 5){
wristPos = (desiredPoint.getY()-startPoint.getY())/(desiredPoint.getDistance(startPoint))*s+startPoint.getY();
}
if (desiredPoint.getDistance(startPoint) <= 5){
s = desiredPoint.getDistance(startPoint);
}
SmartDashboard.putNumber("ArmPathFollow writePos", wristPos);
SmartDashboard.putNumber("ArmPathFollow desiredWrite", desiredPoint.getY());
armSubsystem.pathFollow(Rotation2d.fromDegrees(shoulderPos), Rotation2d.fromDegrees(wristPos));
SmartDashboard.putNumber("ArmPathFollow shoulderPos", shoulderPos);
SmartDashboard.putNumber("ArmPathFollow desiredWrist", desiredPoint.getY());
SmartDashboard.putNumber("ArmPathFollow desiredShoulder", desiredPoint.getX());
armSubsystem.pathFollow(Rotation2d.fromDegrees(shoulderPos), Rotation2d.fromDegrees(wristPos), wristVel, shoulderVel);

armSubsystem.setWristDestState(wristPos);
armSubsystem.setShoulderDesState(shoulderPos);
currPos = new Translation2d(armSubsystem.shoulderState().getDegrees(), armSubsystem.wristState().getDegrees());
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
public void end(boolean interrupted) {
System.out.println("finished this command");
System.out.println(s);
armSubsystem.setWristDestState(desiredPoint.getY());
armSubsystem.setShoulderDesState(desiredPoint.getX());
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return s >= startPoint.getDistance(desiredPoint);
return Math.abs(s - startPoint.getDistance(desiredPoint)) <= .1;
//return currPos.getDistance(desiredPoint) <= 5;
}
}
80 changes: 80 additions & 0 deletions src/main/java/frc/robot/commands/AutoDriveToNoteCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
package frc.robot.commands;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.SwerveDrive;
import frc.robot.vision.Vision;


public class AutoDriveToNoteCommand extends Command {

private final Vision vision;
private final SwerveDrive subsystem;

private Translation2d target = null;
private int idleLoopCount = 0;
private double speed;
private double speedMultiplier;
public AutoDriveToNoteCommand(SwerveDrive subsystem, Vision vision, double SpeedMultiplier){
this.vision = vision;
this.subsystem = subsystem;
this.speedMultiplier=SpeedMultiplier;
addRequirements(subsystem);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
this.target = null;
idleLoopCount = 0;
}

private void updateTarget() {
var robotPose = subsystem.getEstimatedPose();
var detectionMaxThreshold = Double.POSITIVE_INFINITY;
if (target != null) {
detectionMaxThreshold = robotPose.getTranslation().getDistance(target) + Units.feetToMeters(2);
}

var detections = vision.detections();
for (var detection : detections){
var distance = detection.getNorm();
if (distance < detectionMaxThreshold){
var detectionFieldCoord = robotPose.transformBy(new Transform2d(detection, new Rotation2d())).getTranslation();
target = detectionFieldCoord;
detectionMaxThreshold = distance;
}
}
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
updateTarget();
if (target == null){
idleLoopCount += 1;
}
// Drive towards target
var robotPose = subsystem.getEstimatedPose();
var delta = target.minus(robotPose.getTranslation());
speed = speedMultiplier*target.getDistance(robotPose.getTranslation())/Units.inchesToMeters(12);
var unitDelta = delta.div(delta.getNorm()).times(speed);
var robotAngle = unitDelta.getAngle();
subsystem.setDesiredYaw(robotAngle.getDegrees());
subsystem.driveAtSpeed(unitDelta.getX(), unitDelta.getY(), 0, true);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
subsystem.stopModules();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
15 changes: 4 additions & 11 deletions src/main/java/frc/robot/commands/ClimbDown.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,17 +41,10 @@ public void initialize() {
public void execute() {


if(climber.canGoUpRight()){
climber.driveRight(speed);
} else {
climber.driveRight(0);
}

if(climber.canGoUpLeft()){
climber.driveLeft(speed);
} else {
climber.driveLeft(0);
}


climber.driveLeft(speed);
climber.driveRight(speed);

}
// Called once the command ends or is interrupted.
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/commands/Collect.java
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ public void execute() {
@Override
public void end(boolean interrupted) {
collector.stopCollector();
shouldStop = false;
}

// Returns true when the command should end.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,14 +53,14 @@ public void execute() {
double finalSpeed = 0;

if (buttonOut.get() && !buttonIn.get()) { //collector out
finalSpeed = -speed;
finalSpeed = -1;//speed;
}
if (!buttonOut.get() && buttonIn.get() && !subsystem.isCollected()) { //collector in no note
finalSpeed = speed;
timer.restart();
}
if (subsystem.isCollected() && timer.get() <= .05){
finalSpeed = -speed;
if (subsystem.isCollected() && timer.get() <= .1){
finalSpeed = -speed/3;
}
if(index.get()){
finalSpeed = 1;
Expand Down
129 changes: 129 additions & 0 deletions src/main/java/frc/robot/commands/DriveToNoteCollectCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
package frc.robot.commands;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.CollectorSubsystem;
import frc.robot.subsystems.SwerveDrive;
import frc.robot.vision.Vision;

import java.util.function.DoubleConsumer;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;

public class DriveToNoteCollectCommand extends Command {

private final Vision vision;
private final SwerveDrive subsystem;
private final DoubleSupplier speedSupplier;
private final DoubleConsumer rumbleCallback;
private boolean shouldStop = false;
private Timer timer;

private final CollectorSubsystem collector;

private Translation2d target = null;
private int idleLoopCount = 0;

// public DriveToNoteCollectCommand(SwerveDrive subsystem, Vision vision, DoubleSupplier speedSupplier) {
// this(subsystem, vision, speedSupplier, null,);
// }
public DriveToNoteCollectCommand(SwerveDrive subsystem, Vision vision, DoubleSupplier speedSupplier, DoubleConsumer rumbleCallback, CollectorSubsystem collector){
this.speedSupplier = speedSupplier;
this.vision = vision;
this.subsystem = subsystem;
this.rumbleCallback = rumbleCallback;
this.collector = collector;
shouldStop=false;
addRequirements(subsystem,collector);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
this.target = null;
idleLoopCount = 0;
shouldStop=false;
}

private void updateTarget() {
var robotPose = subsystem.getEstimatedPose();
var detectionMaxThreshold = Double.POSITIVE_INFINITY;
if (target != null) {
detectionMaxThreshold = robotPose.getTranslation().getDistance(target) + Units.feetToMeters(2);
}

var detections = vision.detections();
for (var detection : detections){
var distance = detection.getNorm();
if (distance < detectionMaxThreshold){
var detectionFieldCoord = robotPose.transformBy(new Transform2d(detection, new Rotation2d())).getTranslation();
target = detectionFieldCoord;
detectionMaxThreshold = distance;
}
}
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double finalSpeed = 0;
updateTarget();
if (target == null){
idleLoopCount += 1;

if (idleLoopCount >= 5 && rumbleCallback != null){
rumbleCallback.accept(1);
}
return;
}
// Drive towards target
var robotPose = subsystem.getEstimatedPose();
var delta = target.minus(robotPose.getTranslation());
var unitDelta = delta.div(delta.getNorm()).times(speedSupplier.getAsDouble());

var robotAngle = unitDelta.getAngle();
subsystem.setDesiredYaw(robotAngle.getDegrees());

subsystem.driveAtSpeed(unitDelta.getX(), unitDelta.getY(), 0, true);

if (delta.getNorm()<=Units.feetToMeters(1)&& !shouldStop && !collector.isCollected()) { //within 1 ft, collector in, no note
finalSpeed = 0.4;
timer.restart();
}
/* if (collector.isCollected() && timer.get() <= .1){
shouldStop = true;
finalSpeed = -0.4;
}*/
collector.updateCollectorSpeed(finalSpeed);
SmartDashboard.putBoolean("started collector", collector.getCollectorState());
SmartDashboard.putNumber("collector speed", finalSpeed);

SmartDashboard.putBoolean("Should Stop", shouldStop);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
if (rumbleCallback != null){
rumbleCallback.accept(0);
}
shouldStop=false;
collector.stopCollector();
subsystem.stopModules();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
if(shouldStop && timer.get() >= .1){
return true;
}
return false;
}
}
Loading

0 comments on commit 8a3fbb5

Please sign in to comment.