Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/vision/LineupMaster.java
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,8 @@ public static ReefFace getClosestReefFace(Pose2d robotPose){
}

public Command directDriveToPose(Pose2d targetPose) {
return new DriveToPoseCommand(targetPose);
return new AutoAlign(targetPose);
// return new DriveToPoseCommand(targetPose);
}

public Command directDriveToNearestLeftBranch() {
Expand Down
42 changes: 16 additions & 26 deletions src/main/java/frc/robot/vision/commands/AutoAlign.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,25 +4,15 @@
import static edu.wpi.first.units.Units.Inches;
import static edu.wpi.first.units.Units.Meters;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.MetersPerSecondPerSecond;
import static edu.wpi.first.units.Units.Radians;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond;
import static frc.robot.vision.VisionConfig.AlignmentConfig.*;

import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.swerve.SwerveModule.SteerRequestType;
import com.ctre.phoenix6.swerve.SwerveRequest;
import com.ctre.phoenix6.swerve.SwerveRequest.FieldCentric;
import com.ctre.phoenix6.swerve.SwerveRequest.ForwardPerspectiveValue;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.Distance;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -82,7 +72,7 @@ public AutoAlign(Pose2d targetPose) {
*/
public AutoAlign(
CommandSwerveDrivetrain drivetrainSubsystem,
Supplier<Pose2d> poseProvider) {
Supplier<Pose2d> goalPose) {

// this.drivetrainSubsystem = CommandSwerveDrivetrain.getInstance();
// this.poseProvider = () -> PoseEstimatorSubsystem.getInstance().getCurrentPose();
Expand Down Expand Up @@ -111,12 +101,20 @@ public void setGoal(Pose2d goalPose) {
yController.setSetpoint(goalPose.getY());
}

private ChassisSpeeds applyLimits(ChassisSpeeds speeds){
Translation2d translation = new Translation2d(speeds.vxMetersPerSecond, speeds.vyMetersPerSecond);
double magnitude = translation.getNorm();
if (magnitude < .07) return new ChassisSpeeds(0,0, speeds.omegaRadiansPerSecond);
Rotation2d angle = translation.getAngle();
magnitude = Math.min(magnitude, MAX_ALIGN_TRANSLATION_VELOCITY.in(MetersPerSecond));
return new ChassisSpeeds(magnitude * angle.getCos(), magnitude * angle.getSin(), speeds.omegaRadiansPerSecond);
}

@Override
public void initialize() {
var robotPose = poseProvider.get();
thetaController.reset();
xController.reset();
yController.reset();
thetaController.reset();
}

@Override
Expand All @@ -138,10 +136,12 @@ public void execute() {
omegaSpeed = 0;
}

ChassisSpeeds speeds = applyLimits(new ChassisSpeeds(xSpeed, ySpeed, omegaSpeed));

CommandSwerveDrivetrain.getInstance().applyRequest( () ->
RobotContainer.drive.withVelocityX(xSpeed)
.withVelocityY(ySpeed)
.withRotationalRate(omegaSpeed)
RobotContainer.drive.withVelocityX(speeds.vxMetersPerSecond)
.withVelocityY(speeds.vyMetersPerSecond)
.withRotationalRate(speeds.omegaRadiansPerSecond)
).execute();
// drivetrainSubsystem.setControl(
// fieldCentricSwerveRequest.withVelocityX(xSpeed).withVelocityY(ySpeed).withRotationalRate(omegaSpeed));
Expand All @@ -156,14 +156,4 @@ public boolean isFinished() {
public void end(boolean interrupted) {
drivetrainSubsystem.setControl(new SwerveRequest.Idle());
}

private ChassisSpeeds applyLimits(ChassisSpeeds speeds){
Translation2d translation = new Translation2d(speeds.vxMetersPerSecond, speeds.vyMetersPerSecond);
double magnitude = translation.getNorm();
if (magnitude < .07) return new ChassisSpeeds(0,0, speeds.omegaRadiansPerSecond);
Rotation2d angle = translation.getAngle();
magnitude = Math.min(magnitude, MAX_ALIGN_TRANSLATION_VELOCITY.in(MetersPerSecond));
return new ChassisSpeeds(magnitude * angle.getCos(), magnitude * angle.getSin(), speeds.omegaRadiansPerSecond);
}

}