Skip to content
Closed
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
66 changes: 28 additions & 38 deletions src/main/java/frc/robot/subsystems/swervedrive/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
Expand All @@ -47,7 +47,7 @@

import frc.robot.utils.NetworkTablesUtils;
import org.json.simple.parser.ParseException;
import org.photonvision.PhotonCamera;
import org.photonvision.EstimatedRobotPose;
import org.photonvision.targeting.PhotonPipelineResult;
import swervelib.SwerveController;
import swervelib.SwerveDrive;
Expand All @@ -61,10 +61,10 @@

public class SwerveSubsystem extends SubsystemBase
{
private final NetworkTablesUtils NTUtils = NetworkTablesUtils.getTable("debug");
//TODO: add swerve constants
private final PIDController drivePID = new PIDController(0, 0, 0);
private final PIDController turnPID = new PIDController(0, 0, 0);
//TODO javadoc
private final PIDController drivePid = new PIDController(0, 0, 0);
private final NetworkTablesUtils table = NetworkTablesUtils.getTable("debug");

/**
* Swerve drive object.
*/
Expand Down Expand Up @@ -153,6 +153,12 @@ public void periodic()
swerveDrive.updateOdometry();
vision.updatePoseEstimation(swerveDrive);
}

// Update Translation to some point
// TODO: Change 0, 0, 0 to diff values
table.setEntry("GoToX", swerveDrive.getMaximumChassisVelocity() * drivePid.calculate(swerveDrive.getPose().getX(), table.getEntry("DesiredX", 0)));
table.setEntry("GoToY", swerveDrive.getMaximumChassisVelocity() * drivePid.calculate(swerveDrive.getPose().getY(), table.getEntry("DesiredY", 0)));
table.setEntry("GoToAng", swerveDrive.getMaximumChassisAngularVelocity() * drivePid.calculate(swerveDrive.getPose().getRotation().getRotations(), table.getEntry("DesiredAng", 0)));
}

@Override
Expand Down Expand Up @@ -602,38 +608,6 @@ public void zeroGyroWithAlliance()
}
}

public boolean driveToPoint(Pose2d point, double tolerance, double maxVel, double maxRVel, double robotYComp, boolean isContinuous) {
double xVel, yVel, rVel;
double translationMag;

drivePID.setSetpoint(0.0);
turnPID.setSetpoint(point.getRotation().getRadians());

Translation2d difference = point.minus(swerveDrive.getPose()).getTranslation();

if (isContinuous) {
translationMag = maxVel;
}
else {
translationMag = -DrivetrainConstants.MAX_DRIVE_VELOCITY_MPS * drivePID.calculate(Math.sqrt(Math.pow(difference.getX(), 2) + Math.pow(difference.getY(), 2)));
}

xVel = translationMag * Math.cos(difference.getAngle().getRadians());
yVel = translationMag * Math.sin(difference.getAngle().getRadians());
rVel = DrivetrainConstants.MAX_ANGULAR_SPEED * turnPID.calculate(swerveDrive.getYaw().getRadians());
if (rVel > 0) {
rVel = Math.min(rVel, maxRVel);
}
else {
rVel = Math.max(rVel, -maxRVel);
}
Translation2d driveVals = new Translation2d(xVel, yVel);

drive(driveVals, rVel, true);

return drivePID.atSetpoint() && turnPID.atSetpoint();
}

/**
* Sets the drive motors to brake/coast mode.
*
Expand Down Expand Up @@ -771,4 +745,20 @@ public SwerveDrive getSwerveDrive()
{
return swerveDrive;
}

//TODO: Javadoc
public void DriveToPoint(Pose2d desiredPose)
{
table.setEntry("DesiredX", desiredPose.getX());
table.setEntry("DesiredY", desiredPose.getY());
table.setEntry("DesiredAng", desiredPose.getRotation().getRotations());

this.drive(
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

drive uses velocities instead of positions

new Translation2d(
table.getEntry("GoToX", 0),
table.getEntry("GoToY", 0)),
table.getEntry("GoToAng", 0),
true
);
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/swervedrive/Vision.java
Original file line number Diff line number Diff line change
Expand Up @@ -333,7 +333,7 @@ public void updateVisionField()
/**
* Camera Enum to select each camera
*/
enum Cameras
public enum Cameras
{
/**
* Left Camera
Expand Down