Skip to content
New issue

Have a question about this project? # for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “#”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? # to your account

Cleanup and fix usage of constants #163

Merged
merged 1 commit into from
Jan 31, 2024
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
13 changes: 6 additions & 7 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,11 @@

package frc.robot;

import com.pathplanner.lib.util.PIDConstants;

import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;
import swervelib.math.Matter;
import swervelib.parser.PIDFConfig;

/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean constants. This
Expand All @@ -24,16 +25,14 @@ public final class Constants
public static final Matter CHASSIS = new Matter(new Translation3d(0, 0, Units.inchesToMeters(8)), ROBOT_MASS);
public static final double LOOP_TIME = 0.13; //s, 20ms + 110ms sprk max velocity lag

public static final class Auton
public static final class AutonConstants
{

public static final PIDFConfig TranslationPID = new PIDFConfig(0.7, 0, 0);
public static final PIDFConfig angleAutoPID = new PIDFConfig(0.4, 0, 0.01);

public static final double MAX_ACCELERATION = 2;
public static final PIDConstants TRANSLATION_PID = new PIDConstants(0.7, 0, 0);
public static final PIDConstants ANGLE_PID = new PIDConstants(0.4, 0, 0.01);
}

public static final class Drivebase
public static final class DrivebaseConstants
{

// Hold time on motor brakes when disabled
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ public void disabledInit()
@Override
public void disabledPeriodic()
{
if (disabledTimer.hasElapsed(Constants.Drivebase.WHEEL_LOCK_TIME))
if (disabledTimer.hasElapsed(Constants.DrivebaseConstants.WHEEL_LOCK_TIME))
{
m_robotContainer.setMotorBrake(false);
disabledTimer.stop();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import com.pathplanner.lib.path.PathConstraints;
import com.pathplanner.lib.path.PathPlannerPath;
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;
Expand All @@ -22,6 +21,7 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
import frc.robot.Constants.AutonConstants;
import java.io.File;
import java.util.function.DoubleSupplier;
import swervelib.SwerveController;
Expand Down Expand Up @@ -105,11 +105,9 @@ public void setupPathPlanner()
this::getRobotVelocity, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
this::setChassisSpeeds, // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds
new HolonomicPathFollowerConfig( // HolonomicPathFollowerConfig, this should likely live in your Constants class
new PIDConstants(5.0, 0.0, 0.0),
AutonConstants.TRANSLATION_PID,
// Translation PID constants
new PIDConstants(swerveDrive.swerveController.config.headingPIDF.p,
swerveDrive.swerveController.config.headingPIDF.i,
swerveDrive.swerveController.config.headingPIDF.d),
AutonConstants.ANGLE_PID,
// Rotation PID constants
4.5,
// Max module speed, in m/s
Expand Down