Skip to content
Closed
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
58 changes: 48 additions & 10 deletions src/main/java/frc/trigon/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,45 +6,46 @@
package frc.trigon.robot;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.commands.PathPlannerAuto;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.trigon.robot.commands.CommandConstants;
import frc.trigon.robot.commands.commandfactories.AutonomousCommands;
import frc.trigon.robot.commands.commandfactories.CoralCollectionCommands;
import frc.trigon.robot.commands.commandfactories.GeneralCommands;
import frc.trigon.robot.constants.AutonomousConstants;
import frc.trigon.robot.constants.CameraConstants;
import frc.trigon.robot.constants.LEDConstants;
import frc.trigon.robot.constants.OperatorConstants;
import frc.trigon.robot.constants.PathPlannerConstants;
import frc.trigon.robot.misc.objectdetectioncamera.ObjectPoseEstimator;
import frc.trigon.robot.misc.simulatedfield.SimulatedGamePieceConstants;
import frc.trigon.robot.poseestimation.poseestimator.PoseEstimator;
import frc.trigon.robot.subsystems.MotorSubsystem;

import frc.trigon.robot.subsystems.elevator.Elevator;
import frc.trigon.robot.subsystems.elevator.ElevatorCommands;
import frc.trigon.robot.subsystems.elevator.ElevatorConstants;
import frc.trigon.robot.subsystems.arm.Arm;
import frc.trigon.robot.subsystems.arm.ArmCommands;
import frc.trigon.robot.subsystems.arm.ArmConstants;

import frc.trigon.robot.subsystems.climber.Climber;
import frc.trigon.robot.subsystems.climber.ClimberCommands;
import frc.trigon.robot.subsystems.climber.ClimberConstants;
import frc.trigon.robot.subsystems.elevator.Elevator;
import frc.trigon.robot.subsystems.elevator.ElevatorCommands;
import frc.trigon.robot.subsystems.elevator.ElevatorConstants;
import frc.trigon.robot.subsystems.intake.Intake;
import frc.trigon.robot.subsystems.intake.IntakeCommands;
import frc.trigon.robot.subsystems.intake.IntakeConstants;

import frc.trigon.robot.subsystems.swerve.Swerve;
import frc.trigon.robot.subsystems.transporter.Transporter;
import frc.trigon.robot.subsystems.transporter.TransporterCommands;
import frc.trigon.robot.subsystems.transporter.TransporterConstants;
import lib.utilities.flippable.Flippable;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

import java.util.List;

public class RobotContainer {
public static final PoseEstimator ROBOT_POSE_ESTIMATOR = new PoseEstimator();
public static final ObjectPoseEstimator OBJECT_POSE_ESTIMATOR = new ObjectPoseEstimator(
public static final ObjectPoseEstimator CORAL_POSE_ESTIMATOR = new ObjectPoseEstimator(
CameraConstants.OBJECT_POSE_ESTIMATOR_DELETION_THRESHOLD_SECONDS,
ObjectPoseEstimator.DistanceCalculationMethod.ROTATION_AND_TRANSLATION,
SimulatedGamePieceConstants.GamePieceType.GAME_PIECE_TYPE,
Expand Down Expand Up @@ -94,7 +95,7 @@ private void bindDefaultCommands() {
private void initializeGeneralSystems() {
Flippable.init();
LEDConstants.init();
PathPlannerConstants.init();
AutonomousConstants.init();
}

private void bindControllerCommands() {
Expand All @@ -113,7 +114,44 @@ private void configureSysIDBindings(MotorSubsystem subsystem) {
subsystem.setDefaultCommand(Commands.idle(subsystem));
}

@SuppressWarnings("All")
private void buildAutoChooser() {
autoChooser = new LoggedDashboardChooser<>("AutoChooser", AutoBuilder.buildAutoChooser());
autoChooser = new LoggedDashboardChooser<>("AutoChooser");

final List<String> autoNames = AutoBuilder.getAllAutoNames();
boolean hasDefault = false;

for (String autoName : autoNames) {
final PathPlannerAuto autoNonMirrored = new PathPlannerAuto(autoName);
final PathPlannerAuto autoMirrored = new PathPlannerAuto(autoName, true);

if (!AutonomousConstants.DEFAULT_AUTO_NAME.isEmpty() && AutonomousConstants.DEFAULT_AUTO_NAME.equals(autoName)) {
hasDefault = true;
autoChooser.addDefaultOption(autoNonMirrored.getName(), autoNonMirrored);
autoChooser.addOption(autoMirrored.getName() + "Mirrored", autoMirrored);
} else if (!AutonomousConstants.DEFAULT_AUTO_NAME.isEmpty() && AutonomousConstants.DEFAULT_AUTO_NAME.equals(autoName + "Mirrored")) {
hasDefault = true;
autoChooser.addDefaultOption(autoMirrored.getName() + "Mirrored", autoMirrored);
autoChooser.addOption(autoNonMirrored.getName(), autoNonMirrored);
} else {
autoChooser.addOption(autoNonMirrored.getName(), autoNonMirrored);
autoChooser.addOption(autoMirrored.getName() + "Mirrored", autoMirrored);
}
}

if (!hasDefault)
autoChooser.addDefaultOption("None", Commands.none());
else
autoChooser.addOption("None", Commands.none());

addCommandsToChooser(
AutonomousCommands.getFloorAutonomousCommand(true),
AutonomousCommands.getFloorAutonomousCommand(false)
);
}

private void addCommandsToChooser(Command... commands) {
for (Command command : commands)
autoChooser.addOption(command.getName(), command);
}
}
4 changes: 2 additions & 2 deletions src/main/java/frc/trigon/robot/commands/CommandConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.trigon.robot.RobotContainer;
import frc.trigon.robot.commands.commandfactories.GeneralCommands;
import frc.trigon.robot.constants.AutonomousConstants;
import frc.trigon.robot.constants.OperatorConstants;
import frc.trigon.robot.constants.PathPlannerConstants;
import frc.trigon.robot.subsystems.swerve.SwerveCommands;
import lib.commands.CameraPositionCalculationCommand;
import lib.commands.WheelRadiusCharacterizationCommand;
Expand Down Expand Up @@ -45,7 +45,7 @@ public class CommandConstants {
() -> calculateRotationStickAxisValue(DRIVER_CONTROLLER.getRightX())
),
WHEEL_RADIUS_CHARACTERIZATION_COMMAND = new WheelRadiusCharacterizationCommand(
PathPlannerConstants.ROBOT_CONFIG.moduleLocations,
AutonomousConstants.ROBOT_CONFIG.moduleLocations,
RobotContainer.SWERVE::getDriveWheelPositionsRadians,
() -> RobotContainer.SWERVE.getHeading().getRadians(),
(omegaRadiansPerSecond) -> RobotContainer.SWERVE.selfRelativeDriveWithoutSetpointGeneration(new ChassisSpeeds(0, 0, omegaRadiansPerSecond), null),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,28 +6,25 @@
import edu.wpi.first.wpilibj2.command.*;
import frc.trigon.robot.RobotContainer;
import frc.trigon.robot.commands.commandfactories.GeneralCommands;
import frc.trigon.robot.constants.PathPlannerConstants;
import frc.trigon.robot.constants.AutonomousConstants;
import frc.trigon.robot.misc.objectdetectioncamera.ObjectPoseEstimator;
import frc.trigon.robot.misc.simulatedfield.SimulatedGamePieceConstants;
import frc.trigon.robot.subsystems.swerve.SwerveCommands;
import org.littletonrobotics.junction.Logger;
import lib.utilities.flippable.FlippableRotation2d;
import org.littletonrobotics.junction.Logger;

import java.util.function.Supplier;

public class GamePieceAutoDriveCommand extends ParallelCommandGroup {
private static final ObjectPoseEstimator OBJECT_POSE_ESTIMATOR = RobotContainer.OBJECT_POSE_ESTIMATOR;
private final SimulatedGamePieceConstants.GamePieceType targetGamePieceType;
private static final ObjectPoseEstimator CORAL_POSE_ESTIMATOR = RobotContainer.CORAL_POSE_ESTIMATOR;
private Translation2d distanceFromTrackedGamePiece;

public GamePieceAutoDriveCommand(SimulatedGamePieceConstants.GamePieceType targetGamePieceType) {
this.targetGamePieceType = targetGamePieceType;
public GamePieceAutoDriveCommand() {
addCommands(
getTrackGamePieceCommand(),
GeneralCommands.getContinuousConditionalCommand(
getDriveToGamePieceCommand(() -> distanceFromTrackedGamePiece),
GeneralCommands.getFieldRelativeDriveCommand(),
() -> OBJECT_POSE_ESTIMATOR.getClosestObjectToRobot() != null && shouldMoveTowardsGamePiece(distanceFromTrackedGamePiece)
() -> CORAL_POSE_ESTIMATOR.getClosestObjectToRobot() != null && shouldMoveTowardsGamePiece(distanceFromTrackedGamePiece)
)
);
}
Expand All @@ -40,36 +37,36 @@ private Command getTrackGamePieceCommand() {

public static Translation2d calculateDistanceFromTrackedGamePiece() {
final Pose2d robotPose = RobotContainer.ROBOT_POSE_ESTIMATOR.getEstimatedRobotPose();
final Translation2d trackedObjectPositionOnField = OBJECT_POSE_ESTIMATOR.getClosestObjectToRobot();
final Translation2d trackedObjectPositionOnField = CORAL_POSE_ESTIMATOR.getClosestObjectToRobot();
if (trackedObjectPositionOnField == null)
return null;

final Translation2d robotToGamePiece = robotPose.getTranslation().minus(trackedObjectPositionOnField);
var distanceFromTrackedGamePiece = robotToGamePiece.rotateBy(robotPose.getRotation().unaryMinus());
Logger.recordOutput("GamePieceAutoDrive/DistanceFromTrackedGamePiece", distanceFromTrackedGamePiece);
Logger.recordOutput("GamePieceAutoDrive/XDistanceFromTrackedGamePiece", PathPlannerConstants.GAME_PIECE_AUTO_DRIVE_X_PID_CONTROLLER.getSetpoint().position);
Logger.recordOutput("GamePieceAutoDrive/XDistanceFromTrackedGamePiece", AutonomousConstants.GAME_PIECE_AUTO_DRIVE_X_PID_CONTROLLER.getSetpoint().position);
return distanceFromTrackedGamePiece;
}

public static Command getDriveToGamePieceCommand(Supplier<Translation2d> distanceFromTrackedGamePiece) {
return new SequentialCommandGroup(
new InstantCommand(() -> PathPlannerConstants.GAME_PIECE_AUTO_DRIVE_X_PID_CONTROLLER.reset(distanceFromTrackedGamePiece.get().getX(), RobotContainer.SWERVE.getSelfRelativeVelocity().vxMetersPerSecond)),
new InstantCommand(() -> AutonomousConstants.GAME_PIECE_AUTO_DRIVE_X_PID_CONTROLLER.reset(distanceFromTrackedGamePiece.get().getX(), RobotContainer.SWERVE.getSelfRelativeVelocity().vxMetersPerSecond)),
SwerveCommands.getClosedLoopSelfRelativeDriveCommand(
() -> PathPlannerConstants.GAME_PIECE_AUTO_DRIVE_X_PID_CONTROLLER.calculate(distanceFromTrackedGamePiece.get().getX()),
() -> PathPlannerConstants.GAME_PIECE_AUTO_DRIVE_Y_PID_CONTROLLER.calculate(distanceFromTrackedGamePiece.get().getY()),
() -> AutonomousConstants.GAME_PIECE_AUTO_DRIVE_X_PID_CONTROLLER.calculate(distanceFromTrackedGamePiece.get().getX()),
() -> AutonomousConstants.GAME_PIECE_AUTO_DRIVE_Y_PID_CONTROLLER.calculate(distanceFromTrackedGamePiece.get().getY()),
GamePieceAutoDriveCommand::calculateTargetAngle
)
);
}

public static boolean shouldMoveTowardsGamePiece(Translation2d distanceFromTrackedGamePiece) {
return distanceFromTrackedGamePiece != null &&
(distanceFromTrackedGamePiece.getNorm() > PathPlannerConstants.AUTO_COLLECTION_INTAKE_OPEN_CHECK_DISTANCE_METERS);//TODO: If intake is open
(distanceFromTrackedGamePiece.getNorm() > AutonomousConstants.AUTO_COLLECTION_INTAKE_OPEN_CHECK_DISTANCE_METERS);//TODO: If intake is open
}

public static FlippableRotation2d calculateTargetAngle() {
final Pose2d robotPose = RobotContainer.ROBOT_POSE_ESTIMATOR.getEstimatedRobotPose();
final Translation2d trackedObjectFieldRelativePosition = OBJECT_POSE_ESTIMATOR.getClosestObjectToRobot();
final Translation2d trackedObjectFieldRelativePosition = CORAL_POSE_ESTIMATOR.getClosestObjectToRobot();
if (trackedObjectFieldRelativePosition == null)
return null;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,16 +11,16 @@
import frc.trigon.robot.commands.commandfactories.GeneralCommands;
import frc.trigon.robot.constants.OperatorConstants;
import frc.trigon.robot.subsystems.swerve.SwerveCommands;
import org.littletonrobotics.junction.Logger;
import lib.hardware.RobotHardwareStats;
import org.littletonrobotics.junction.Logger;

import java.util.function.Supplier;

/**
* A command class to assist in the intaking of a game piece.
*/
public class IntakeAssistCommand extends ParallelCommandGroup {
private static final ProfiledPIDController
static final ProfiledPIDController
X_PID_CONTROLLER = RobotHardwareStats.isSimulation() ?
new ProfiledPIDController(0.5, 0, 0, new TrapezoidProfile.Constraints(2.8, 5)) :
new ProfiledPIDController(2.4, 0, 0, new TrapezoidProfile.Constraints(2.65, 5.5)),
Expand All @@ -43,7 +43,7 @@ public IntakeAssistCommand(AssistMode assistMode) {
GeneralCommands.getContinuousConditionalCommand(
GeneralCommands.getFieldRelativeDriveCommand(),
getAssistIntakeCommand(assistMode, () -> distanceFromTrackedGamePiece),
() -> RobotContainer.OBJECT_POSE_ESTIMATOR.getClosestObjectToRobot() == null || distanceFromTrackedGamePiece == null
() -> RobotContainer.CORAL_POSE_ESTIMATOR.getClosestObjectToRobot() == null || distanceFromTrackedGamePiece == null
)
);
}
Expand All @@ -53,7 +53,7 @@ public IntakeAssistCommand(AssistMode assistMode) {
* This command is for intaking a game piece with a specific robot-relative position.
* To create an intake assist command that selects the closest game piece automatically, use {@link IntakeAssistCommand#IntakeAssistCommand(AssistMode)} instead.
*
* @param assistMode the type of assistance
* @param assistMode the type of assistance
* @param distanceFromTrackedGamePiece the position of the game piece relative to the robot
* @return the command
*/
Expand All @@ -70,21 +70,21 @@ public static Command getAssistIntakeCommand(AssistMode assistMode, Supplier<Tra

private Command getTrackGamePieceCommand() {
return new RunCommand(() -> {
if (RobotContainer.OBJECT_POSE_ESTIMATOR.getClosestObjectToRobot() != null)
if (RobotContainer.CORAL_POSE_ESTIMATOR.getClosestObjectToRobot() != null)
distanceFromTrackedGamePiece = calculateDistanceFromTrackedCGamePiece();
});
}

private static Translation2d calculateDistanceFromTrackedCGamePiece() {
public static Translation2d calculateDistanceFromTrackedCGamePiece() {
final Pose2d robotPose = RobotContainer.ROBOT_POSE_ESTIMATOR.getEstimatedRobotPose();
final Translation2d trackedObjectPositionOnField = RobotContainer.OBJECT_POSE_ESTIMATOR.getClosestObjectToRobot();
final Translation2d trackedObjectPositionOnField = RobotContainer.CORAL_POSE_ESTIMATOR.getClosestObjectToRobot();
if (trackedObjectPositionOnField == null)
return null;

final Translation2d difference = robotPose.getTranslation().minus(trackedObjectPositionOnField);
final Translation2d robotToTrackedGamepieceDistance = difference.rotateBy(robotPose.getRotation().unaryMinus());
Logger.recordOutput("IntakeAssist/TrackedGamePieceDistance", robotToTrackedGamepieceDistance);
return robotToTrackedGamepieceDistance;
final Translation2d robotToTrackedGamePieceDistance = difference.rotateBy(robotPose.getRotation().unaryMinus());
Logger.recordOutput("IntakeAssist/TrackedGamePieceDistance", robotToTrackedGamePieceDistance);
return robotToTrackedGamePieceDistance;
}

private static Translation2d calculateTranslationPower(AssistMode assistMode, Translation2d distanceFromTrackedGamepiece) {
Expand Down
Loading
Loading