Skip to content

Commit e688476

Browse files
committed
adicionar mais configurações para o swerve
1 parent 5dbea16 commit e688476

File tree

2 files changed

+10
-7
lines changed

2 files changed

+10
-7
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@ public static final class Controle {
4646
}
4747

4848
public static final class SwerveConfigs {
49+
// variável que ativa o PID para controlar a orientação do robô (PID tunado no json)
50+
public static final boolean headingCorrection = false;
4951
// true para correção de aceleração
5052
public static final boolean accelCorrection = false;
5153
// constante para diminuir o input do joystick (0 < multiplicadorRotacional <= 1)
@@ -54,11 +56,10 @@ public static final class SwerveConfigs {
5456
public static final double multiplicadorTranslacionalY = 0.7;
5557
// constante para diminuir o input do joystick (x)
5658
public static final double multiplicadorTranslacionalX = 0.7;
57-
5859
public static final double TURN_CONSTANT = 0.75;
59-
60-
public static final double dt = 0.02;
61-
62-
public static final double constantRotation = 4;
60+
// variável que ativa a coração para resolver problema de "skew"
61+
public static final boolean usarCorrecaoDesvioVelocidadeAngular = false;
62+
// constante que corrije o skew (de -0.15 - 0.15) ESSA VARIÁVEL DEVE SER TUNADA PARA SEU ROBÔ
63+
public static final double coeficienteCoreçãoAngVel = 4;
6364
}
6465
}

src/main/java/frc/robot/subsystems/SwerveSubsystem.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,6 @@
99

1010
import com.pathplanner.lib.auto.AutoBuilder;
1111
import com.pathplanner.lib.commands.PathPlannerAuto;
12-
import com.pathplanner.lib.commands.PathfindingCommand;
1312
import com.pathplanner.lib.config.PIDConstants;
1413
import com.pathplanner.lib.config.RobotConfig;
1514
import com.pathplanner.lib.controllers.PPHolonomicDriveController;
@@ -22,6 +21,7 @@
2221
import edu.wpi.first.wpilibj2.command.Command;
2322
import edu.wpi.first.wpilibj2.command.SubsystemBase;
2423
import frc.robot.Constants;
24+
import frc.robot.Constants.SwerveConfigs;
2525
import swervelib.SwerveController;
2626
import swervelib.SwerveDrive;
2727
import swervelib.telemetry.SwerveDriveTelemetry;
@@ -47,7 +47,9 @@ public SwerveSubsystem(File directory) {
4747
} catch (Exception e) {
4848
throw new RuntimeException(e);
4949
}
50-
swerveDrive.setHeadingCorrection(true);
50+
swerveDrive.setHeadingCorrection(Constants.SwerveConfigs.headingCorrection);
51+
swerveDrive.angularVelocityCorrection = SwerveConfigs.usarCorrecaoDesvioVelocidadeAngular;
52+
swerveDrive.angularVelocityCoefficient = SwerveConfigs.coeficienteCoreçãoAngVel;
5153
setupPathPlanner();
5254
}
5355

0 commit comments

Comments
 (0)