Skip to content
Open
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
73 changes: 73 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -159,3 +159,76 @@ imgui.ini


# End of https://www.gitignore.io/api/c++,java,linux,macos,gradle,windows,visualstudiocode


# Covers JetBrains IDEs: IntelliJ, RubyMine, PhpStorm, AppCode, PyCharm, CLion, Android Studio, WebStorm and Rider
# Reference: https://intellij-support.jetbrains.com/hc/en-us/articles/206544839

# User-specific stuff
.idea/**/workspace.xml
.idea/**/tasks.xml
.idea/**/usage.statistics.xml
.idea/**/dictionaries
.idea/**/shelf

# Generated files
.idea/**/contentModel.xml

# Sensitive or high-churn files
.idea/**/dataSources/
.idea/**/dataSources.ids
.idea/**/dataSources.local.xml
.idea/**/sqlDataSources.xml
.idea/**/dynamic.xml
.idea/**/uiDesigner.xml
.idea/**/dbnavigator.xml

# Gradle
.idea/**/gradle.xml
.idea/**/libraries

# Gradle and Maven with auto-import
# When using Gradle or Maven with auto-import, you should exclude module files,
# since they will be recreated, and may cause churn. Uncomment if using
# auto-import.
# .idea/artifacts
# .idea/compiler.xml
# .idea/jarRepositories.xml
# .idea/modules.xml
# .idea/*.iml
# .idea/modules
# *.iml
# *.ipr

# CMake
cmake-build-*/

# Mongo Explorer plugin
.idea/**/mongoSettings.xml

# File-based project format
*.iws

# IntelliJ
out/

# mpeltonen/sbt-idea plugin
.idea_modules/

# JIRA plugin
atlassian-ide-plugin.xml

# Cursive Clojure plugin
.idea/replstate.xml

# Crashlytics plugin (for Android Studio and IntelliJ)
com_crashlytics_export_strings.xml
crashlytics.properties
crashlytics-build.properties
fabric.properties

# Editor-based Rest Client
.idea/httpRequests

# Android studio 3.1+ serialized cache file
.idea/caches/build_file_checksums.ser
145 changes: 145 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,145 @@
package frc.robot;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/**
* 你好朋友!Be sure to read the following header documentation for a better of this class, and how to use it.
* <br />
* <br />
* <p>
* Starting with all the static constants (declared as public static final double), these values are only declared here,
* and are not added to the SmartDashboard. Since it can only be edited here,
* if you want to make a change you will have to change it in the code and then recompile. Not ideal,
* but hopefully for those constants you wont be changing those often.
* <p>
* However there are a few constants that you will want to edit without the need to recompile.
* For that you will use the SmartDashboard to display and edit those vales, but retrieving those can be somewhat tedious.
* <p>
* THis class aims to make that less tedious, and more intuitive.
* <p>
* To declare a new constant that you want to use within the SmartDashboard,
* use {@code public static final Constants k = new Constants("k", 10.0d)}.
* This will create an entry within SmartDashboard for k. To retrieve the values of K, use {@code k.getValue()}.
* <p>
* Once you have found a good default value, you can then return to the source code and adjust it here,
* and then recompile for next time.
*
* @author Spud
*/
public class Constants {

/**
* Setpoint Shooting constants
*/
public static final double shooterPower = 0.7d;
public static final Constants feedSpeed = new Constants("feedSpeed", 5700d),
feedRatio = new Constants("feedRatio", 0.2d);

/**
* Limelight and navX constants
*/
public static final Constants taShoot = new Constants("taShoot", 0.1d),
txShoot = new Constants("txShoot", 0.0d),
tyShoot = new Constants("tyShoot", 0.0d),
tx_kp = new Constants("tx_kp", 0.017d),
tx_ki = new Constants("tx_ki", 0.00002d),
tx_kd = new Constants("tx_kd", 0.0d),
tx_iMax = new Constants("tx_iMax", 0.02d),
ty_kp = new Constants("ty_kp", 0.016d),
ty_ki = new Constants("ty_ki", 0.0001d),
ty_kd = new Constants("ty_kd", 0.0d),
ahrs_kp = new Constants("ahrs_kp", 0.0002d),
ahrs_ki = new Constants("ahrs_ki", 0.000001d),
ahrs_kd = new Constants("ahrs_kd", 0.000001d);

/**
* Shooter constants
*/
public static final double visionCenterHeight = 89.4d, //should be 89.75 base on official guild
cameraHeight = 6.6d, cameraAngle = 31d, distanceModifier = 1.115d,
gearRatioLow = 14.88d, gearRatioHigh = 6.55d, wheelRotationToInch = Math.PI * 6, shooterHeight = 20.0d,
g = 386.2d, goalHeight = 98.25d, shooterAngleMax = 65.0d, shooterAngleMin = 30.0d, goalDepth = 29.25d;
public static final Constants targetDistance = new Constants("targetDistance", 120.0d);

/**
* PID Constants (What are these used for?)
*/
public static final double maxRPM = 5700d, dp_kp = 0.0018d,
dp_ki = 0.000002d, dp_kd = 0.000001d,
dp_kiz = 500d, dp_kff = 0.000175d;

/**
* Shooter PID constants
*/
public static final Constants s_kp = new Constants("s_kp", 0.00010d),
s_ki = new Constants("s_ki", 0.0000001d),
s_kd = new Constants("s_kd", 0.0d),
s_kiz = new Constants("s_kiz", 1000d),
s_kff = new Constants("s_kff", 0.000175d),
s_kMaxOutput = new Constants("s_kMaxOutput", 0.0d),
s_kMinOutput = new Constants("s_kMinOutput", -1.0d),
s_iAccum = new Constants("s_iAccum", 0.0d);

/**
* Revolver PID constants
*/
public static final Constants r_kp = new Constants("r_kp", 0.0001d),
r_ki = new Constants("r_ki", 0.000000d),
r_kd = new Constants("r_kd", 0.0d),
r_kiz = new Constants("r_kiz", 0.0d),
r_kff = new Constants("r_kff", 0.0002d);

/**
* Feeder PID constants
*/
public static final Constants f_kp = new Constants("f_kp", 0.0001d),
f_ki = new Constants("f_ki", 0.0000010d),
f_kd = new Constants("f_kd", 0.0d),
f_kiz = new Constants("f_kiz", 1500.0d),
f_kff = new Constants("f_kff", 0.00019d);

/**
* Drivertrain PID Constants
*/
public static final Constants dv_kp = new Constants("dv_kp", 0.000005d),
dv_ki = new Constants("dv_ki", 0.0000005d),
dv_kd = new Constants("dv_kd", 0.000001d),
dv_kiz = new Constants("dv_kiz", 500.0d),
dv_kff = new Constants("dv_kff", 0.000175d);

/**
* The key of the value used by Smartdashboard.
* This is never really used by the end user other than in the SmartDashboard, so it doesn't need a getter method.
*/
protected String key;

/**
* The value of the constant.
* Because this will be retrieved from the SmartDashboard a custom getter method should be used.
*/
private double value;

/**
* Creates a constant value that will be added to the SmartDashboard.
*
* @param key The key of the constant. Aside from being used on SmartDashboard,
* this value is never accessed outside this class.
* @param defaultValue The default value of this constant. If nothing is provided within SmartDashboard for this entry,
* this value will be returned instead.
*/
public Constants(String key, double defaultValue) {
this.key = key;
this.value = defaultValue;
SmartDashboard.putNumber(this.key, this.value);
}

/**
* Gets the value of the constant from SmartDashboard. This will always return a value.
* Even if nothing is in SmartDashboard, the default value provided at the constructor of the constant will be returned.
*
* @return The value of the constant from SmartDashboard.
*/
public double getValue() {
return SmartDashboard.getNumber(this.key, this.value);
}
}
148 changes: 0 additions & 148 deletions src/main/java/frc/robot/Motor.java

This file was deleted.

Loading