Compare commits
2 Commits
93e789e07a
...
d43d9655ac
Author | SHA1 | Date | |
---|---|---|---|
d43d9655ac | |||
6cb76c01b2 |
@ -12,6 +12,7 @@ public class ShooterConstants {
|
|||||||
public static final double kEncoderConversionFactor = 0;
|
public static final double kEncoderConversionFactor = 0;
|
||||||
|
|
||||||
public static final double kBangBangTolerance = 0;
|
public static final double kBangBangTolerance = 0;
|
||||||
|
public static final double kBangBangVoltageMultiplier = 10;
|
||||||
|
|
||||||
public static final double kFFS = 0;
|
public static final double kFFS = 0;
|
||||||
public static final double kFFV = 0;
|
public static final double kFFV = 0;
|
||||||
|
@ -53,7 +53,7 @@ public class Shooter extends SubsystemBase {
|
|||||||
double output = controller.calculate(
|
double output = controller.calculate(
|
||||||
(motor1Encoder.getRate() + motor2Encoder.getRate()) / 2,
|
(motor1Encoder.getRate() + motor2Encoder.getRate()) / 2,
|
||||||
speed
|
speed
|
||||||
) + ff.calculate(speed);
|
) * ShooterConstants.kBangBangVoltageMultiplier + ff.calculate(speed);
|
||||||
|
|
||||||
motor1.setVoltage(output);
|
motor1.setVoltage(output);
|
||||||
});
|
});
|
||||||
|
@ -20,8 +20,8 @@ import edu.wpi.first.util.WPIUtilJNI;
|
|||||||
import edu.wpi.first.wpilibj.ADIS16470_IMU;
|
import edu.wpi.first.wpilibj.ADIS16470_IMU;
|
||||||
import edu.wpi.first.wpilibj.ADIS16470_IMU.IMUAxis;
|
import edu.wpi.first.wpilibj.ADIS16470_IMU.IMUAxis;
|
||||||
import frc.robot.constants.DrivetrainConstants;
|
import frc.robot.constants.DrivetrainConstants;
|
||||||
import frc.utils.MAXSwerveModule;
|
import frc.robot.utils.MAXSwerveModule;
|
||||||
import frc.utils.SwerveUtils;
|
import frc.robot.utils.SwerveUtils;
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
// Open Source Software; you can modify and/or share it under the terms of
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
// the WPILib BSD license file in the root directory of this project.
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
package frc.utils;
|
package frc.robot.utils;
|
||||||
|
|
||||||
import edu.wpi.first.math.geometry.Rotation2d;
|
import edu.wpi.first.math.geometry.Rotation2d;
|
||||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
@ -1,4 +1,4 @@
|
|||||||
package frc.utils;
|
package frc.robot.utils;
|
||||||
|
|
||||||
public class SwerveUtils {
|
public class SwerveUtils {
|
||||||
|
|
@ -0,0 +1,31 @@
|
|||||||
|
{
|
||||||
|
"version": 1.0,
|
||||||
|
"startingPose": {
|
||||||
|
"position": {
|
||||||
|
"x": 2.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"rotation": 0
|
||||||
|
},
|
||||||
|
"command": {
|
||||||
|
"type": "sequential",
|
||||||
|
"data": {
|
||||||
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "path",
|
||||||
|
"data": {
|
||||||
|
"pathName": "New Path"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": null
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"folder": null,
|
||||||
|
"choreoAuto": false
|
||||||
|
}
|
File diff suppressed because one or more lines are too long
@ -0,0 +1,68 @@
|
|||||||
|
{
|
||||||
|
"version": 1.0,
|
||||||
|
"waypoints": [
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 2.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"prevControl": null,
|
||||||
|
"nextControl": {
|
||||||
|
"x": 3.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 4.9219209708544644,
|
||||||
|
"y": 4.185419462073272
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 3.9219209708544644,
|
||||||
|
"y": 4.185419462073272
|
||||||
|
},
|
||||||
|
"nextControl": {
|
||||||
|
"x": 5.921920970854464,
|
||||||
|
"y": 4.185419462073272
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 7.124773319314081,
|
||||||
|
"y": 4.185419462073272
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 6.67504098644561,
|
||||||
|
"y": 3.190431108134944
|
||||||
|
},
|
||||||
|
"nextControl": null,
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"rotationTargets": [],
|
||||||
|
"constraintZones": [],
|
||||||
|
"eventMarkers": [],
|
||||||
|
"globalConstraints": {
|
||||||
|
"maxVelocity": 3.0,
|
||||||
|
"maxAcceleration": 3.0,
|
||||||
|
"maxAngularVelocity": 540.0,
|
||||||
|
"maxAngularAcceleration": 720.0
|
||||||
|
},
|
||||||
|
"goalEndState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": -91.7272598416291,
|
||||||
|
"rotateFast": false
|
||||||
|
},
|
||||||
|
"reversed": false,
|
||||||
|
"folder": null,
|
||||||
|
"previewStartingState": {
|
||||||
|
"rotation": 0,
|
||||||
|
"velocity": 0
|
||||||
|
},
|
||||||
|
"useDefaultConstraints": true
|
||||||
|
}
|
@ -0,0 +1,100 @@
|
|||||||
|
{
|
||||||
|
"version": 1.0,
|
||||||
|
"waypoints": [
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 2.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"prevControl": null,
|
||||||
|
"nextControl": {
|
||||||
|
"x": 3.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 2.6077077608723753,
|
||||||
|
"y": 0.578382247674906
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 1.6077077608723753,
|
||||||
|
"y": 0.578382247674906
|
||||||
|
},
|
||||||
|
"nextControl": {
|
||||||
|
"x": 3.6077077608723753,
|
||||||
|
"y": 0.578382247674906
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 9.585609716676286,
|
||||||
|
"y": 1.026162052325425
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 9.52815390120199,
|
||||||
|
"y": -0.017618595457612685
|
||||||
|
},
|
||||||
|
"nextControl": {
|
||||||
|
"x": 9.641582192257601,
|
||||||
|
"y": 2.0429953587193106
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 8.512803934698777,
|
||||||
|
"y": 7.602927933128594
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 8.765079824050103,
|
||||||
|
"y": 7.436655187872565
|
||||||
|
},
|
||||||
|
"nextControl": {
|
||||||
|
"x": 8.102339113771444,
|
||||||
|
"y": 7.873461565106268
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 6.572424781213199,
|
||||||
|
"y": 7.2857505715011435
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 6.2272611817974,
|
||||||
|
"y": 7.127161890688737
|
||||||
|
},
|
||||||
|
"nextControl": null,
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"rotationTargets": [],
|
||||||
|
"constraintZones": [],
|
||||||
|
"eventMarkers": [],
|
||||||
|
"globalConstraints": {
|
||||||
|
"maxVelocity": 3.0,
|
||||||
|
"maxAcceleration": 3.0,
|
||||||
|
"maxAngularVelocity": 540.0,
|
||||||
|
"maxAngularAcceleration": 720.0
|
||||||
|
},
|
||||||
|
"goalEndState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": 13.828650972347063,
|
||||||
|
"rotateFast": false
|
||||||
|
},
|
||||||
|
"reversed": false,
|
||||||
|
"folder": null,
|
||||||
|
"previewStartingState": {
|
||||||
|
"rotation": 0,
|
||||||
|
"velocity": 0
|
||||||
|
},
|
||||||
|
"useDefaultConstraints": true
|
||||||
|
}
|
@ -12,6 +12,9 @@ import com.pathplanner.lib.auto.NamedCommands;
|
|||||||
import edu.wpi.first.wpilibj.DriverStation;
|
import edu.wpi.first.wpilibj.DriverStation;
|
||||||
import edu.wpi.first.wpilibj.XboxController;
|
import edu.wpi.first.wpilibj.XboxController;
|
||||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||||
import frc.robot.constants.OIConstants;
|
import frc.robot.constants.OIConstants;
|
||||||
import frc.robot.subsystems.Drivetrain;
|
import frc.robot.subsystems.Drivetrain;
|
||||||
@ -42,12 +45,12 @@ public class RobotContainer {
|
|||||||
drivetrain = new Drivetrain();
|
drivetrain = new Drivetrain();
|
||||||
driver = new CommandXboxController(OIConstants.kDriverControllerPort);
|
driver = new CommandXboxController(OIConstants.kDriverControllerPort);
|
||||||
|
|
||||||
NamedCommands.registerCommand("Set Drivetrain X", drivetrain.setXCommand());
|
|
||||||
|
|
||||||
autoChooser = AutoBuilder.buildAutoChooser();
|
autoChooser = AutoBuilder.buildAutoChooser();
|
||||||
|
|
||||||
// Configure the button bindings
|
// Configure the button bindings
|
||||||
configureButtonBindings();
|
configureButtonBindings();
|
||||||
|
configureShuffleboard();
|
||||||
|
configureNamedCommands();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -86,6 +89,19 @@ public class RobotContainer {
|
|||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private void configureShuffleboard() {
|
||||||
|
ShuffleboardTab autoTab = Shuffleboard.getTab(OIConstants.kAutoTabName);
|
||||||
|
|
||||||
|
autoTab.add("Auto Selection", autoChooser)
|
||||||
|
.withPosition(0, 0)
|
||||||
|
.withSize(2, 1)
|
||||||
|
.withWidget(BuiltInWidgets.kComboBoxChooser);
|
||||||
|
}
|
||||||
|
|
||||||
|
private void configureNamedCommands() {
|
||||||
|
NamedCommands.registerCommand("Set Drivetrain X", drivetrain.setXCommand());
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use this to pass the autonomous command to the main {@link Robot} class.
|
* Use this to pass the autonomous command to the main {@link Robot} class.
|
||||||
*
|
*
|
||||||
|
@ -3,4 +3,6 @@ package frc.robot.constants;
|
|||||||
public class OIConstants {
|
public class OIConstants {
|
||||||
public static final int kDriverControllerPort = 0;
|
public static final int kDriverControllerPort = 0;
|
||||||
public static final double kDriveDeadband = 0.05;
|
public static final double kDriveDeadband = 0.05;
|
||||||
|
|
||||||
|
public static final String kAutoTabName = "Autonomous";
|
||||||
}
|
}
|
||||||
|
@ -1,18 +1,18 @@
|
|||||||
{
|
{
|
||||||
"fileName": "PathplannerLib.json",
|
"fileName": "PathplannerLib2024.json",
|
||||||
"name": "PathplannerLib",
|
"name": "PathplannerLib",
|
||||||
"version": "2024.2.7",
|
"version": "2024.2.8",
|
||||||
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
|
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
|
||||||
"frcYear": "2024",
|
"frcYear": "2024",
|
||||||
"mavenUrls": [
|
"mavenUrls": [
|
||||||
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
|
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
|
||||||
],
|
],
|
||||||
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
|
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib2024.json",
|
||||||
"javaDependencies": [
|
"javaDependencies": [
|
||||||
{
|
{
|
||||||
"groupId": "com.pathplanner.lib",
|
"groupId": "com.pathplanner.lib",
|
||||||
"artifactId": "PathplannerLib-java",
|
"artifactId": "PathplannerLib-java",
|
||||||
"version": "2024.2.7"
|
"version": "2024.2.8"
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
"jniDependencies": [],
|
"jniDependencies": [],
|
||||||
@ -20,7 +20,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.pathplanner.lib",
|
"groupId": "com.pathplanner.lib",
|
||||||
"artifactId": "PathplannerLib-cpp",
|
"artifactId": "PathplannerLib-cpp",
|
||||||
"version": "2024.2.7",
|
"version": "2024.2.8",
|
||||||
"libName": "PathplannerLib",
|
"libName": "PathplannerLib",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": false,
|
"sharedLibrary": false,
|
||||||
@ -35,4 +35,4 @@
|
|||||||
]
|
]
|
||||||
}
|
}
|
||||||
]
|
]
|
||||||
}
|
}
|
Loading…
Reference in New Issue
Block a user