Skip to content

Commit

Permalink
Ran spotless apply
Browse files Browse the repository at this point in the history
  • Loading branch information
IanTapply22 committed Nov 12, 2023
1 parent cf9ffae commit 9ed0977
Show file tree
Hide file tree
Showing 6 changed files with 955 additions and 896 deletions.
123 changes: 67 additions & 56 deletions src/main/java/frc/robot/CommandSwerveDrivetrain.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
package frc.robot;

import java.util.function.Supplier;

import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrain;
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
Expand All @@ -11,75 +9,88 @@
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.function.Supplier;

/**
* Class that extends the Phoenix SwerveDrivetrain class and implements subsystem
* so it can be used in command-based projects easily.
* Class that extends the Phoenix SwerveDrivetrain class and implements subsystem so it can be used
* in command-based projects easily.
*/
public class CommandSwerveDrivetrain extends SwerveDrivetrain implements Subsystem {
private SwerveRequest.ApplyChassisSpeeds autoRequest = new SwerveRequest.ApplyChassisSpeeds();
public CommandSwerveDrivetrain(SwerveDrivetrainConstants driveTrainConstants, double OdometryUpdateFrequency, SwerveModuleConstants... modules) {
super(driveTrainConstants, OdometryUpdateFrequency, modules);
configurePathPlanner();
}
public CommandSwerveDrivetrain(SwerveDrivetrainConstants driveTrainConstants, SwerveModuleConstants... modules) {
super(driveTrainConstants, modules);
configurePathPlanner();
}
private SwerveRequest.ApplyChassisSpeeds autoRequest = new SwerveRequest.ApplyChassisSpeeds();

private void configurePathPlanner() {
AutoBuilder.configureHolonomic(
()->this.getState().Pose, // Supplier of current robot pose
this::seedFieldRelative, // Consumer for seeding pose against auto
this::getCurrentRobotChassisSpeeds,
(speeds)->this.setControl(autoRequest.withSpeeds(speeds)), // Consumer of ChassisSpeeds to drive the robot
new HolonomicPathFollowerConfig(new PIDConstants(10, 0, 0),
new PIDConstants(10, 0, 0),
1,
1,
new ReplanningConfig(),
0.004),
this); // Subsystem for requirements
}
public CommandSwerveDrivetrain(
SwerveDrivetrainConstants driveTrainConstants,
double OdometryUpdateFrequency,
SwerveModuleConstants... modules) {
super(driveTrainConstants, OdometryUpdateFrequency, modules);
configurePathPlanner();
}

public Command applyRequest(Supplier<SwerveRequest> requestSupplier) {
return new RunCommand(()->{this.setControl(requestSupplier.get());}, this);
}
public CommandSwerveDrivetrain(
SwerveDrivetrainConstants driveTrainConstants, SwerveModuleConstants... modules) {
super(driveTrainConstants, modules);
configurePathPlanner();
}

public Command getAutoPath(String pathName) {
return new PathPlannerAuto(pathName);
}
private void configurePathPlanner() {
AutoBuilder.configureHolonomic(
() -> this.getState().Pose, // Supplier of current robot pose
this::seedFieldRelative, // Consumer for seeding pose against auto
this::getCurrentRobotChassisSpeeds,
(speeds) ->
this.setControl(
autoRequest.withSpeeds(speeds)), // Consumer of ChassisSpeeds to drive the robot
new HolonomicPathFollowerConfig(
new PIDConstants(10, 0, 0),
new PIDConstants(10, 0, 0),
1,
1,
new ReplanningConfig(),
0.004),
this); // Subsystem for requirements
}

@Override
public void simulationPeriodic() {
/* Assume */
updateSimState(0.02, 12);
}
/**
* Takes the specified location and makes it the current pose for
* field-relative maneuvers
*
* @param location Pose to make the current pose at.
*/
@Override
public void seedFieldRelative(Pose2d location) {
try {
m_stateLock.writeLock().lock();
public Command applyRequest(Supplier<SwerveRequest> requestSupplier) {
return new RunCommand(
() -> {
this.setControl(requestSupplier.get());
},
this);
}

m_odometry.resetPosition(Rotation2d.fromDegrees(m_pigeon2.getYaw().getValue()), m_modulePositions, location);
} finally {
m_stateLock.writeLock().unlock();
}
}
public Command getAutoPath(String pathName) {
return new PathPlannerAuto(pathName);
}

@Override
public void simulationPeriodic() {
/* Assume */
updateSimState(0.02, 12);
}
/**
* Takes the specified location and makes it the current pose for field-relative maneuvers
*
* @param location Pose to make the current pose at.
*/
@Override
public void seedFieldRelative(Pose2d location) {
try {
m_stateLock.writeLock().lock();

public ChassisSpeeds getCurrentRobotChassisSpeeds() {
return m_kinematics.toChassisSpeeds(getState().ModuleStates);
m_odometry.resetPosition(
Rotation2d.fromDegrees(m_pigeon2.getYaw().getValue()), m_modulePositions, location);
} finally {
m_stateLock.writeLock().unlock();
}
}

public ChassisSpeeds getCurrentRobotChassisSpeeds() {
return m_kinematics.toChassisSpeeds(getState().ModuleStates);
}
}
Loading

0 comments on commit 9ed0977

Please sign in to comment.