Compare commits
2 Commits
ba57959f4d
...
85da1dcad1
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
85da1dcad1 | ||
|
|
a92a7a0ea1 |
@@ -33,7 +33,6 @@ public class GrimperMur extends Command {
|
||||
double angle;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
@@ -63,14 +62,14 @@ public class GrimperMur extends Command {
|
||||
y = 2.961328;
|
||||
x = 1.11;
|
||||
angle = 0;
|
||||
if(pigeon2.getYaw().getValueAsDouble() > 355 || pigeon2.getYaw().getValueAsDouble() < 5){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 355 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 5){
|
||||
drivetrain.setControl(drive.withVelocityX(y-boty).withVelocityY(x-botx));
|
||||
}
|
||||
else{
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
}
|
||||
@@ -79,14 +78,14 @@ public class GrimperMur extends Command {
|
||||
x = 11.45966;
|
||||
y = 6.959326;
|
||||
angle = 180;
|
||||
if(pigeon2.getYaw().getValueAsDouble() > 175 && pigeon2.getYaw().getValueAsDouble() < 185){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 175 && drivetrain.getPigeon2().getYaw().getValueAsDouble() < 185){
|
||||
drivetrain.setControl(drive.withVelocityX(y-boty).withVelocityY(x-botx));
|
||||
}
|
||||
else{
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -33,7 +33,6 @@ public class GrimperReservoir extends Command {
|
||||
double angle;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
@@ -63,14 +62,14 @@ public class GrimperReservoir extends Command {
|
||||
y = 5.081328;
|
||||
x = 1.11;
|
||||
angle = 180;
|
||||
if(pigeon2.getYaw().getValueAsDouble() < 185 && pigeon2.getYaw().getValueAsDouble() > 175){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() < 185 && drivetrain.getPigeon2().getYaw().getValueAsDouble() > 175){
|
||||
drivetrain.setControl(drive.withVelocityX(y-boty).withVelocityY(x-botx));
|
||||
}
|
||||
else{
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
}
|
||||
@@ -79,14 +78,14 @@ public class GrimperReservoir extends Command {
|
||||
y = 6.959326;
|
||||
x = 13.57966;
|
||||
angle = 0;
|
||||
if(pigeon2.getYaw().getValueAsDouble() > 355 || pigeon2.getYaw().getValueAsDouble() < 5){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 355 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 5){
|
||||
drivetrain.setControl(drive.withVelocityX(y-boty).withVelocityY(x-botx));
|
||||
}
|
||||
else{
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -30,7 +30,6 @@ public class RetourMilieuDroite extends Command {
|
||||
double angle;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
@@ -58,7 +57,7 @@ public class RetourMilieuDroite extends Command {
|
||||
x = 2.305;
|
||||
angle = 0;
|
||||
if(limelight3g.getV()){
|
||||
if(pigeon2.getYaw().getValueAsDouble() >355 || pigeon2.getYaw().getValueAsDouble() < 5){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >355 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 5){
|
||||
if((y-boty < 0.05 && y-boty >-0.05) && (x-botx < 0.05 && x-botx > -0.05)){
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0));
|
||||
}
|
||||
@@ -72,10 +71,10 @@ public class RetourMilieuDroite extends Command {
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(pigeon2.getYaw().getValueAsDouble() >angle && pigeon2.getYaw().getValueAsDouble() <angle +180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() <angle +180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >=angle +180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >=angle +180){
|
||||
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
@@ -88,10 +87,10 @@ public class RetourMilieuDroite extends Command {
|
||||
angle = 180;
|
||||
if(limelight3g.getV()){
|
||||
}
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -30,7 +30,6 @@ public class RetourMilieuGauche extends Command {
|
||||
double angle;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
@@ -63,7 +62,7 @@ public class RetourMilieuGauche extends Command {
|
||||
x = 2.305;
|
||||
angle = 0;
|
||||
if(limelight3g.getV()){
|
||||
if(pigeon2.getYaw().getValueAsDouble() >355 || pigeon2.getYaw().getValueAsDouble() < 5){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >355 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 5){
|
||||
if((y-boty < 0.05 && y-boty >-0.05) && (x-botx < 0.05 && x-botx > -0.05)){
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0));
|
||||
}
|
||||
@@ -77,10 +76,10 @@ public class RetourMilieuGauche extends Command {
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(pigeon2.getYaw().getValueAsDouble() >angle && pigeon2.getYaw().getValueAsDouble() <angle +180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() <angle +180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >=angle +180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >=angle +180){
|
||||
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
@@ -92,7 +91,7 @@ public class RetourMilieuGauche extends Command {
|
||||
x = 13.963;
|
||||
angle = 180;
|
||||
if(limelight3g.getV()){
|
||||
if(pigeon2.getYaw().getValueAsDouble() >175 && pigeon2.getYaw().getValueAsDouble() < 185){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >175 && drivetrain.getPigeon2().getYaw().getValueAsDouble() < 185){
|
||||
if((y-boty < 0.05 && y-boty >-0.05) && (x-botx < 0.05 && x-botx > -0.05)){
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0));
|
||||
}
|
||||
@@ -106,10 +105,10 @@ public class RetourMilieuGauche extends Command {
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >=180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >=180){
|
||||
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
|
||||
@@ -23,7 +23,6 @@ public class TournerVersMur extends Command {
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
double force;
|
||||
double angle;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
@@ -51,10 +50,10 @@ public class TournerVersMur extends Command {
|
||||
force = -0.5;
|
||||
angle = 180;
|
||||
}
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble()>0 && drivetrain.getPigeon2().getYaw().getValueAsDouble()<180){
|
||||
drivetrain.setControl(drive.withRotationalRate(force));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble()>180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-force));
|
||||
}
|
||||
}
|
||||
@@ -66,6 +65,6 @@ public class TournerVersMur extends Command {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return pigeon2.getYaw().getValueAsDouble() > angle && pigeon2.getYaw().getValueAsDouble() < angle + 5;
|
||||
return drivetrain.getPigeon2().getYaw().getValueAsDouble()> angle && drivetrain.getPigeon2().getYaw().getValueAsDouble()< angle + 5;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -23,7 +23,6 @@ public class TournerVersReservoir extends Command {
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
double force;
|
||||
double angle;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
@@ -51,10 +50,10 @@ public class TournerVersReservoir extends Command {
|
||||
force = -0.5;
|
||||
angle = 0;
|
||||
}
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-force));
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() >180){
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(force));
|
||||
}
|
||||
}
|
||||
@@ -66,6 +65,6 @@ public class TournerVersReservoir extends Command {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return pigeon2.getYaw().getValueAsDouble() > angle && pigeon2.getYaw().getValueAsDouble() < angle + 5;
|
||||
return drivetrain.getPigeon2().getYaw().getValueAsDouble() > angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() < angle + 5;
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user