Skip to content
14 changes: 11 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package frc.robot;

import com.pathplanner.lib.auto.NamedCommands;
import coppercore.wpilib_interface.DriveWithJoysticks;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
Expand All @@ -13,8 +14,8 @@
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction;
import frc.robot.commands.DriveWithJoysticks;
import frc.robot.commands.ShootWithGamepad;
import frc.robot.constants.DriverConstants;
import frc.robot.constants.FeatureFlags;
import frc.robot.constants.ModeConstants;
import frc.robot.constants.PhoenixDriveConstants;
Expand Down Expand Up @@ -303,7 +304,7 @@ private void configureSuppliers() {
private void configureBindings() {
if (drive != null) {
drive.registerTelemetry(logger::telemeterize);
drive.setDefaultCommand(new DriveWithJoysticks(drive, leftJoystick, rightJoystick));
setUpDriveWithJoysticks();
}
if (DriverStation.isTest()) {
// SYS ID
Expand Down Expand Up @@ -761,7 +762,14 @@ public void testInit() {

private void setUpDriveWithJoysticks() {
if (FeatureFlags.runDrive) {
drive.setDefaultCommand(new DriveWithJoysticks(drive, leftJoystick, rightJoystick));
drive.setDefaultCommand(
new DriveWithJoysticks(
drive,
leftJoystick,
rightJoystick,
PhoenixDriveConstants.maxSpeedMetPerSec,
PhoenixDriveConstants.MaxAngularRateRadPerSec,
DriverConstants.leftJoystickDeadband));
}
}
}
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/subsystems/drive/PhoenixDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;
import coppercore.wpilib_interface.DriveTemplate;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
Expand All @@ -29,15 +30,14 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.Subsystem;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.constants.FieldConstants;
import frc.robot.constants.PhoenixDriveConstants;
import frc.robot.constants.PhoenixDriveConstants.AlignTarget;
import java.util.Optional;
import org.littletonrobotics.junction.Logger;

public class PhoenixDrive extends SwerveDrivetrain implements Subsystem {
public class PhoenixDrive extends SwerveDrivetrain implements DriveTemplate {
public enum SysIdRoutineType {
Translation,
Rotation,
Expand Down Expand Up @@ -205,6 +205,7 @@ public ChassisSpeeds getCurrentSpeeds() {
return m_kinematics.toChassisSpeeds(getState().ModuleStates);
}

@Override
public void setGoalSpeeds(ChassisSpeeds goalSpeeds, boolean fieldCentric) {
this.goalSpeeds = goalSpeeds;
this.fieldCentric = fieldCentric;
Expand Down