updated dt constants, auto intaking, pathplanner

This commit is contained in:
Tyler-J42 2024-03-12 04:16:08 -04:00
parent 1119ce0e74
commit 1754ee43a4
11 changed files with 130 additions and 68 deletions

View File

@ -34,6 +34,12 @@
"data": {
"pathName": "L Sub to Center"
}
},
{
"type": "path",
"data": {
"pathName": "Note 1 to Speaker"
}
}
]
}

View File

@ -3,34 +3,58 @@
"waypoints": [
{
"anchor": {
"x": 1.2888463383764373,
"y": 6.642279723305886
"x": 1.1251281761822782,
"y": 6.560420642208806
},
"prevControl": null,
"nextControl": {
"x": 2.2888463383764366,
"y": 6.642279723305886
"x": 1.569506044994996,
"y": 7.098351746561042
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 3.159911049166827,
"y": 6.864468657712245
"x": 2.4114851648506717,
"y": 7.016492665463964
},
"prevControl": {
"x": 2.159911049166827,
"y": 6.864468657712245
"x": 1.943718987153074,
"y": 7.004798511021525
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"rotationTargets": [
{
"waypointRelativePos": 0.45,
"rotationDegrees": 179.22679798216734,
"rotateFast": true
}
],
"constraintZones": [],
"eventMarkers": [],
"eventMarkers": [
{
"name": "New Event Marker",
"waypointRelativePos": 0.1,
"command": {
"type": "parallel",
"data": {
"commands": [
{
"type": "named",
"data": {
"name": "Auto Intake"
}
}
]
}
}
}
],
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
@ -39,13 +63,13 @@
},
"goalEndState": {
"velocity": 0,
"rotation": 0,
"rotation": 180.0,
"rotateFast": false
},
"reversed": false,
"folder": null,
"previewStartingState": {
"rotation": 21.801409486351982,
"rotation": -145.66978280449663,
"velocity": 0
},
"useDefaultConstraints": true

View File

@ -39,7 +39,7 @@
},
"goalEndState": {
"velocity": 0,
"rotation": 149.21037688376774,
"rotation": -128.39665211123375,
"rotateFast": false
},
"reversed": false,

View File

@ -0,0 +1,31 @@
package frc.robot.Commands;
import java.util.function.BooleanSupplier;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.constants.IntakeConstants;
import frc.robot.subsystems.Intake;
public class autoIntaking extends Command{
private Intake m_intake;
private BooleanSupplier m_beamBreak;
public autoIntaking(Intake intake, BooleanSupplier beamBreak){
m_intake = intake;
m_beamBreak = beamBreak;
addRequirements(intake);
}
@Override
public void execute(){
m_intake.intakeControl(() -> IntakeConstants.kDownAngle, () -> 1.0);
}
@Override
public boolean isFinished(){
if(!m_beamBreak.getAsBoolean()){
return true;
}else {return false;}
}
}

View File

@ -30,6 +30,7 @@ import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Commands.autoIntaking;
import frc.robot.constants.IntakeConstants;
import frc.robot.constants.OIConstants;
import frc.robot.constants.PhotonConstants;
@ -102,6 +103,7 @@ public class RobotContainer {
NamedCommands.registerCommand("Charge Shooter 2 Sec", shooter.angleSpeedsSetpoints(() -> ShooterConstants.kShooterLoadAngle, 1.0, 1.0).withTimeout(2.0));
NamedCommands.registerCommand("Speaker Note Shot", Commands.parallel(shooter.angleSpeedsSetpoints(() -> ShooterConstants.kShooterLoadAngle, 1.0, 1.0), indexer.shootNote(() -> 1.0)).withTimeout(2.0));
NamedCommands.registerCommand("Auto Intake", new autoIntaking(intake, indexer::getBeamBreak).andThen(intake.intakeUpCommand()));
// An example Named Command, doesn't need to remain once we start actually adding real things
// ALL Named Commands need to be defined AFTER subsystem initialization and BEFORE auto/controller configuration
@ -168,17 +170,23 @@ public class RobotContainer {
intake.setDefaultCommand(
intake.intakeControl(
() -> {
if (intakeDown) {
if (intakeDown && indexer.getBeamBreak()) {
return IntakeConstants.kDownAngle;
} else {
return IntakeConstants.kUpAngle;
}
},
operator::getRightY
() -> {
if(intakeDown && indexer.getBeamBreak()){
return 1.0;
}else{
return 0.0;
}
}
)
);
operator.povUp().onTrue(
driver.leftTrigger().onFalse(
new InstantCommand(
() -> {
intakeDown = false;
@ -186,7 +194,7 @@ public class RobotContainer {
)
);
operator.povDown().onTrue(
driver.leftTrigger().onTrue(
new InstantCommand(
() -> {
intakeDown = true;

View File

@ -7,7 +7,7 @@ import edu.wpi.first.math.util.Units;
public final class DrivetrainConstants {
// Driving Parameters - Note that these are not the maximum capable speeds of
// the robot, rather the allowed maximum speeds
public static final double kMaxSpeedMetersPerSecond = 4.1;
public static final double kMaxSpeedMetersPerSecond = 5.2;
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
public static final double kDirectionSlewRate = 4.8; // radians per second

View File

@ -49,6 +49,6 @@ public class SwerveModuleConstants {
public static final IdleMode kDrivingMotorIdleMode = IdleMode.kBrake;
public static final IdleMode kTurningMotorIdleMode = IdleMode.kBrake;
public static final int kDrivingMotorCurrentLimit = 65; // amps
public static final int kDrivingMotorCurrentLimit = 70; // amps
public static final int kTurningMotorCurrentLimit = 30; // amps
}

View File

@ -1,6 +1,5 @@
package frc.robot.subsystems;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import com.revrobotics.CANSparkMax;
@ -61,6 +60,29 @@ public class Intake extends SubsystemBase{
armOffset = getIntakeAngle()-IntakeConstants.kStartingAngle;
}
/*
public Command autoIntaking(BooleanSupplier beamBreak){
return run(() -> {
intakeRoller.set(1.0);
intakePivot.setVoltage(
intakeAnglePID.calculate(
getIntakeAngle(),
IntakeConstants.kDownAngle
) + intakeFeedForward.calculate(
IntakeConstants.kDownAngle,
0.0
)
);
return isFinished(() -> {
if(!beamBreak.getAsBoolean()){
return true
}
});
});
}
*/
public Command intakeControl(DoubleSupplier pivotAngle, DoubleSupplier intakeSpeed) {
return run(() -> {
intakeRoller.set(intakeSpeed.getAsDouble());
@ -93,35 +115,6 @@ public class Intake extends SubsystemBase{
});
}
public Command autoIntaking(BooleanSupplier beamBreak){
return run(() -> {
if(beamBreak.getAsBoolean()){
intakeRoller.set(1.0);
intakePivot.setVoltage(
intakeAnglePID.calculate(
getIntakeAngle(),
IntakeConstants.kUpAngle
) + intakeFeedForward.calculate(
IntakeConstants.kUpAngle,
0.0
)
);
}else{
intakeRoller.set(0);
intakePivot.setVoltage(
intakeAnglePID.calculate(
getIntakeAngle(),
IntakeConstants.kDownAngle
) + intakeFeedForward.calculate(
IntakeConstants.kDownAngle,
0.0
)
);
}
});
}
public Command manualPivot(DoubleSupplier pivotPower, DoubleSupplier rollerSpinny){
return run(() ->{
intakePivot.set(pivotPower.getAsDouble());

View File

@ -1,7 +1,7 @@
{
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2024.2.4",
"version": "2024.2.6",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2024",
"mavenUrls": [
@ -12,7 +12,7 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2024.2.4"
"version": "2024.2.6"
}
],
"jniDependencies": [],
@ -20,7 +20,7 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2024.2.4",
"version": "2024.2.6",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,

View File

@ -1,7 +1,7 @@
{
"fileName": "Phoenix5.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.33.0",
"version": "5.33.1",
"frcYear": 2024,
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
@ -20,19 +20,19 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.33.0"
"version": "5.33.1"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.33.0"
"version": "5.33.1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.33.0",
"version": "5.33.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@ -45,7 +45,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.33.0",
"version": "5.33.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@ -60,7 +60,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
@ -75,7 +75,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
@ -90,7 +90,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
@ -105,7 +105,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
@ -120,7 +120,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
@ -135,7 +135,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.33.0",
"version": "5.33.1",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,

View File

@ -1,7 +1,7 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2024.2.2",
"version": "2024.2.3",
"frcYear": "2024",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
@ -12,14 +12,14 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2024.2.2"
"version": "2024.2.3"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2024.2.2",
"version": "2024.2.3",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
@ -37,7 +37,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2024.2.2",
"version": "2024.2.3",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
@ -55,7 +55,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2024.2.2",
"version": "2024.2.3",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,