From a9d088c7c99089ffd6ef3a9ec41782fb07bf62b9 Mon Sep 17 00:00:00 2001 From: aarav18 Date: Sat, 25 Feb 2023 08:52:38 -0700 Subject: [PATCH] real auto --- .../java/frc4388/robot/RobotContainer.java | 64 +------------------ 1 file changed, 1 insertion(+), 63 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index e4e0b39..2982bf5 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -117,69 +117,7 @@ public class RobotContainer { */ public Command getAutonomousCommand() { - //Create Trajectory Settings - TrajectoryConfig trajectoryConfig = new TrajectoryConfig(SwerveDriveConstants.AutoConstants.PATH_MAX_VEL, - SwerveDriveConstants.AutoConstants.PATH_MAX_ACC).setKinematics(m_robotSwerveDrive.getKinematics()); - - // generate trajectory - Trajectory trajectory = TrajectoryGenerator.generateTrajectory( - - new Pose2d(0, 0, new Rotation2d(0)), - List.of( - new Translation2d(0, 1)), - new Pose2d(0, 2, Rotation2d.fromDegrees(0)), - - trajectoryConfig); - - ArrayList simplePath = new ArrayList(); - simplePath.add(new Pose2d(0, 0, new Rotation2d(0))); - simplePath.add(new Pose2d(0, -1, new Rotation2d(0))); - - // Trajectory trajectory = TrajectoryGenerator.generateTrajectory(simplePath, trajectoryConfig); - // Trajectory trajectory = TrajectoryGenerator.generateTrajectory( - // new Pose2d(0, 0, new Rotation2d(0), - // List.of(new Translation2d(0, 1)), - // new Pose2d(0, 2, new Rotation2d(0)), - // trajectoryConfig - // ); - - - // ArrayList states = new ArrayList(); - - - - //Defining PID Controller for tracking trajectory - PIDController xController = new PIDController(SwerveDriveConstants.AutoConstants.X_CONTROLLER.kP, 0, 0); - PIDController yController = new PIDController(SwerveDriveConstants.AutoConstants.Y_CONTROLLER.kP, 0, 0); - ProfiledPIDController thetaController = new ProfiledPIDController(AutoConstants.THETA_CONTROLLER.kP, - AutoConstants.THETA_CONTROLLER.kI, AutoConstants.THETA_CONTROLLER.kD, AutoConstants.THETA_CONSTRAINTS); - thetaController.enableContinuousInput(-Math.PI, Math.PI); - - HolonomicDriveController holoController = new HolonomicDriveController(xController, yController, thetaController); - - //Command to follow trajectory - // SwerveControllerCommand swerveControllerCommand = new SwerveControllerCommand( - // trajectory, - // m_robotSwerveDrive::getOdometry, - // m_robotSwerveDrive.getKinematics(), - // holoController, - // m_robotSwerveDrive::setModuleStates, - // m_robotSwerveDrive); - - SwerveControllerCommand swerveControllerCommand = new SwerveControllerCommand( - trajectory, - m_robotSwerveDrive::getPoseEstimator, - m_robotSwerveDrive.getKinematics(), - holoController, - m_robotSwerveDrive::setModuleStates, - m_robotSwerveDrive); - - //Init and wrap-up, return everything - return new SequentialCommandGroup( - new InstantCommand(() -> m_robotSwerveDrive.resetPoseEstimator(), m_robotSwerveDrive), - // new InstantCommand(() -> m_robotSwerveDrive.setOdometry(trajectory.getInitialPose())), - swerveControllerCommand, - new InstantCommand(() -> m_robotSwerveDrive.stopModules())); + return new JoystickPlayback(m_robotSwerveDrive); } public DeadbandedXboxController getDeadbandedDriverController() {