File tree Expand file tree Collapse file tree 2 files changed +10
-7
lines changed Expand file tree Collapse file tree 2 files changed +10
-7
lines changed Original file line number Diff line number Diff line change @@ -46,6 +46,8 @@ public static final class Controle {
46
46
}
47
47
48
48
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 ;
49
51
// true para correção de aceleração
50
52
public static final boolean accelCorrection = false ;
51
53
// constante para diminuir o input do joystick (0 < multiplicadorRotacional <= 1)
@@ -54,11 +56,10 @@ public static final class SwerveConfigs {
54
56
public static final double multiplicadorTranslacionalY = 0.7 ;
55
57
// constante para diminuir o input do joystick (x)
56
58
public static final double multiplicadorTranslacionalX = 0.7 ;
57
-
58
59
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 ;
63
64
}
64
65
}
Original file line number Diff line number Diff line change 9
9
10
10
import com .pathplanner .lib .auto .AutoBuilder ;
11
11
import com .pathplanner .lib .commands .PathPlannerAuto ;
12
- import com .pathplanner .lib .commands .PathfindingCommand ;
13
12
import com .pathplanner .lib .config .PIDConstants ;
14
13
import com .pathplanner .lib .config .RobotConfig ;
15
14
import com .pathplanner .lib .controllers .PPHolonomicDriveController ;
22
21
import edu .wpi .first .wpilibj2 .command .Command ;
23
22
import edu .wpi .first .wpilibj2 .command .SubsystemBase ;
24
23
import frc .robot .Constants ;
24
+ import frc .robot .Constants .SwerveConfigs ;
25
25
import swervelib .SwerveController ;
26
26
import swervelib .SwerveDrive ;
27
27
import swervelib .telemetry .SwerveDriveTelemetry ;
@@ -47,7 +47,9 @@ public SwerveSubsystem(File directory) {
47
47
} catch (Exception e ) {
48
48
throw new RuntimeException (e );
49
49
}
50
- swerveDrive .setHeadingCorrection (true );
50
+ swerveDrive .setHeadingCorrection (Constants .SwerveConfigs .headingCorrection );
51
+ swerveDrive .angularVelocityCorrection = SwerveConfigs .usarCorrecaoDesvioVelocidadeAngular ;
52
+ swerveDrive .angularVelocityCoefficient = SwerveConfigs .coeficienteCoreçãoAngVel ;
51
53
setupPathPlanner ();
52
54
}
53
55
You can’t perform that action at this time.
0 commit comments