end of pine tree
This commit is contained in:
37
src/main/deploy/pathplanner/autos/Left Shoot.auto
Normal file
37
src/main/deploy/pathplanner/autos/Left Shoot.auto
Normal file
@@ -0,0 +1,37 @@
|
|||||||
|
{
|
||||||
|
"version": "2025.0",
|
||||||
|
"command": {
|
||||||
|
"type": "sequential",
|
||||||
|
"data": {
|
||||||
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "intake down"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "spinup"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "path",
|
||||||
|
"data": {
|
||||||
|
"pathName": "start to score left"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "shoot close"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"resetOdom": true,
|
||||||
|
"folder": null,
|
||||||
|
"choreoAuto": false
|
||||||
|
}
|
||||||
54
src/main/deploy/pathplanner/paths/start to score left.path
Normal file
54
src/main/deploy/pathplanner/paths/start to score left.path
Normal file
@@ -0,0 +1,54 @@
|
|||||||
|
{
|
||||||
|
"version": "2025.0",
|
||||||
|
"waypoints": [
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 3.697342823250297,
|
||||||
|
"y": 6.0
|
||||||
|
},
|
||||||
|
"prevControl": null,
|
||||||
|
"nextControl": {
|
||||||
|
"x": 2.922680901542112,
|
||||||
|
"y": 5.890960854092527
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 2.9872360616844604,
|
||||||
|
"y": 4.599857651245552
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 3.1809015421115063,
|
||||||
|
"y": 5.116298932384343
|
||||||
|
},
|
||||||
|
"nextControl": null,
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"rotationTargets": [],
|
||||||
|
"constraintZones": [],
|
||||||
|
"pointTowardsZones": [],
|
||||||
|
"eventMarkers": [],
|
||||||
|
"globalConstraints": {
|
||||||
|
"maxVelocity": 3.0,
|
||||||
|
"maxAcceleration": 3.0,
|
||||||
|
"maxAngularVelocity": 540.0,
|
||||||
|
"maxAngularAcceleration": 720.0,
|
||||||
|
"nominalVoltage": 12.0,
|
||||||
|
"unlimited": false
|
||||||
|
},
|
||||||
|
"goalEndState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": -22.619864948040433
|
||||||
|
},
|
||||||
|
"reversed": false,
|
||||||
|
"folder": null,
|
||||||
|
"idealStartingState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": 0.0
|
||||||
|
},
|
||||||
|
"useDefaultConstraints": true
|
||||||
|
}
|
||||||
@@ -43,7 +43,7 @@ import frc.robot.utilities.Elastic;
|
|||||||
import frc.robot.utilities.Utilities;
|
import frc.robot.utilities.Utilities;
|
||||||
|
|
||||||
public class RobotContainer {
|
public class RobotContainer {
|
||||||
private PhotonVision vision;
|
// private PhotonVision vision;
|
||||||
private Drivetrain drivetrain;
|
private Drivetrain drivetrain;
|
||||||
private Hood hood;
|
private Hood hood;
|
||||||
private Shooter shooter;
|
private Shooter shooter;
|
||||||
@@ -60,7 +60,7 @@ public class RobotContainer {
|
|||||||
private Timer shiftTimer;
|
private Timer shiftTimer;
|
||||||
|
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
vision = new PhotonVision();
|
//vision = new PhotonVision();
|
||||||
drivetrain = new Drivetrain(null);
|
drivetrain = new Drivetrain(null);
|
||||||
hood = new Hood();
|
hood = new Hood();
|
||||||
shooter = new Shooter();
|
shooter = new Shooter();
|
||||||
@@ -68,8 +68,9 @@ public class RobotContainer {
|
|||||||
intakeRoller = new IntakeRoller();
|
intakeRoller = new IntakeRoller();
|
||||||
spindexer = new Spindexer();
|
spindexer = new Spindexer();
|
||||||
//climber = new Climber();
|
//climber = new Climber();
|
||||||
|
configureNamedCommands();
|
||||||
|
|
||||||
|
/*
|
||||||
vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
|
vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
|
||||||
vision.addPoseEstimateConsumer((vp) -> {
|
vision.addPoseEstimateConsumer((vp) -> {
|
||||||
Logger.recordOutput(
|
Logger.recordOutput(
|
||||||
@@ -77,6 +78,7 @@ public class RobotContainer {
|
|||||||
vp.visualPose()
|
vp.visualPose()
|
||||||
);
|
);
|
||||||
});
|
});
|
||||||
|
*/
|
||||||
|
|
||||||
driver = new CommandXboxController(OIConstants.kDriverControllerPort);
|
driver = new CommandXboxController(OIConstants.kDriverControllerPort);
|
||||||
secondary = new CommandXboxController(OIConstants.kOperatorControllerPort);
|
secondary = new CommandXboxController(OIConstants.kOperatorControllerPort);
|
||||||
@@ -91,7 +93,7 @@ public class RobotContainer {
|
|||||||
if(AutoConstants.kAutoConfigOk) {
|
if(AutoConstants.kAutoConfigOk) {
|
||||||
autoChooser = AutoBuilder.buildAutoChooser();
|
autoChooser = AutoBuilder.buildAutoChooser();
|
||||||
SmartDashboard.putData("Auto Chooser", autoChooser);
|
SmartDashboard.putData("Auto Chooser", autoChooser);
|
||||||
configureNamedCommands();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -268,7 +270,7 @@ public class RobotContainer {
|
|||||||
|
|
||||||
driver.rightTrigger().whileTrue(spindexer.spinToShooter());
|
driver.rightTrigger().whileTrue(spindexer.spinToShooter());
|
||||||
driver.b().whileTrue(spindexer.spinToIntake());
|
driver.b().whileTrue(spindexer.spinToIntake());
|
||||||
driver.b().whileTrue(
|
/* driver.b().whileTrue(
|
||||||
drivetrain.lockToYaw(
|
drivetrain.lockToYaw(
|
||||||
() -> {
|
() -> {
|
||||||
OptionalDouble maybeYaw = vision.getBestYawForTag(Utilities.getHubCenterAprilTagID());
|
OptionalDouble maybeYaw = vision.getBestYawForTag(Utilities.getHubCenterAprilTagID());
|
||||||
@@ -278,13 +280,17 @@ public class RobotContainer {
|
|||||||
driver::getLeftY,
|
driver::getLeftY,
|
||||||
driver::getLeftX
|
driver::getLeftX
|
||||||
)
|
)
|
||||||
);
|
);*/
|
||||||
|
|
||||||
secondary.a().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed));
|
secondary.a().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed));
|
||||||
secondary.x().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kFeedSpeed));
|
secondary.x().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kFeedSpeed));
|
||||||
|
|
||||||
secondary.y().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(40)));
|
secondary.y().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(40)));
|
||||||
|
//40 good for feeding
|
||||||
secondary.b().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(30)));
|
secondary.b().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(30)));
|
||||||
|
//30 degrees good for shooter far near outpost
|
||||||
|
secondary.rightBumper().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(10)));
|
||||||
|
//10 degrees good for shooting ~33in away from hub
|
||||||
|
|
||||||
/*
|
/*
|
||||||
hood.setDefaultCommand(hood.trackToAngle(() -> {
|
hood.setDefaultCommand(hood.trackToAngle(() -> {
|
||||||
@@ -324,14 +330,26 @@ public class RobotContainer {
|
|||||||
false // TODO Should this be true by default?
|
false // TODO Should this be true by default?
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
|
NamedCommands.registerCommand(
|
||||||
|
"intake down",
|
||||||
|
intakePivot.manualSpeed(()->-0.75)
|
||||||
|
.withTimeout(1)
|
||||||
|
);
|
||||||
|
|
||||||
|
NamedCommands.registerCommand("spinup",
|
||||||
|
shooter.maintainSpeed(ShooterSpeeds.kHubSpeed)
|
||||||
|
.withTimeout(3));
|
||||||
|
|
||||||
|
NamedCommands.registerCommand("shoot close",
|
||||||
|
spindexer.spinToShooter()
|
||||||
|
.alongWith(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed))
|
||||||
|
.alongWith(hood.trackToAngle(() -> Units.degreesToRadians(10)))
|
||||||
|
.withTimeout(3));
|
||||||
}
|
}
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
if(AutoConstants.kAutoConfigOk) {
|
|
||||||
return autoChooser.getSelected();
|
return autoChooser.getSelected();
|
||||||
} else {
|
|
||||||
return new PrintCommand("Robot Config loading failed, autonomous disabled");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|||||||
@@ -7,7 +7,7 @@ public class IntakeRollerConstants {
|
|||||||
// TODO Real values
|
// TODO Real values
|
||||||
public static final int kMotorCANID = 20;
|
public static final int kMotorCANID = 20;
|
||||||
|
|
||||||
public static final int kCurrentLimit = 40;
|
public static final int kCurrentLimit = 65;
|
||||||
|
|
||||||
public static final boolean kInvertMotors = true;
|
public static final boolean kInvertMotors = true;
|
||||||
|
|
||||||
|
|||||||
@@ -24,7 +24,7 @@ public class IntakeRoller extends SubsystemBase {
|
|||||||
|
|
||||||
public Command runIn() {
|
public Command runIn() {
|
||||||
return run(() -> {
|
return run(() -> {
|
||||||
motor.set(IntakeRollerConstants.kSpeed);
|
motor.set(IntakeRollerConstants.kSpeed*0.8);
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user