Skip to content
This repository has been archived by the owner on Jan 9, 2025. It is now read-only.

Commit

Permalink
remove slow speed constants from azimuth command (#30)
Browse files Browse the repository at this point in the history
  • Loading branch information
memori034 authored Nov 8, 2024
1 parent 71b85c0 commit ea066f5
Showing 1 changed file with 23 additions and 23 deletions.
46 changes: 23 additions & 23 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -226,9 +226,9 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(-m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(-m_driverController.getLeftX() * SlowMaxSpeed)
.withRotationalRate(-m_driverController.getRightX() * SlowMaxAngular)));
.withVelocityX(-m_driverController.getLeftY())
.withVelocityY(-m_driverController.getLeftX())
.withRotationalRate(-m_driverController.getRightX())));

/* translational and rotational speed are slowed */
m_driverController
Expand Down Expand Up @@ -256,8 +256,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -271,8 +271,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -286,8 +286,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -301,8 +301,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -316,8 +316,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -331,8 +331,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -349,8 +349,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -364,8 +364,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -379,8 +379,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand All @@ -394,8 +394,8 @@ public void configureSwerve() {
swerve.applyRequest(
() ->
drive
.withVelocityX(m_driverController.getLeftY() * SlowMaxSpeed)
.withVelocityY(m_driverController.getLeftX() * SlowMaxSpeed)
.withVelocityX(m_driverController.getLeftY())
.withVelocityY(m_driverController.getLeftX())
.withRotationalRate(
SwerveConstants.azimuthController.calculate(
swerve.getPigeon2().getAngle(),
Expand Down

0 comments on commit ea066f5

Please sign in to comment.