mode auto
This commit is contained in:
@@ -56,7 +56,7 @@ public class Limelighter extends Command {
|
||||
return;
|
||||
}
|
||||
if (alliance.get() == Alliance.Blue) {
|
||||
x = 4.6;
|
||||
x = 4;
|
||||
}
|
||||
else {
|
||||
x = 11.915394;
|
||||
@@ -64,30 +64,28 @@ public class Limelighter extends Command {
|
||||
botx = BotPose[1];
|
||||
boty = BotPose[0];
|
||||
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||
if(calcul < -5 && calcul > -180){
|
||||
calcul = limelight3g.Calcule(botx, x, boty, 4.6, angle);
|
||||
if(calcul < -3 && calcul > -180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
drive.withRotationalRate(-1.5));
|
||||
}
|
||||
else if(calcul > 5 && calcul < 180){
|
||||
else if(calcul > 3 && calcul < 180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
drive.withRotationalRate(-1.5));
|
||||
}
|
||||
else if(calcul >= 180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
drive.withRotationalRate(-1.5));
|
||||
}
|
||||
else if(calcul <= -180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
drive.withRotationalRate(1.5));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0));
|
||||
}
|
||||
drivetrain.setControl(
|
||||
drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
|
||||
System.out.println(angle);
|
||||
}
|
||||
System.out.println(calcul);
|
||||
if (calcul < 0.2 && calcul > -0.2) {
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
|
||||
@@ -60,7 +60,7 @@ public class GrimperMur extends Command {
|
||||
angle = angle + 360;
|
||||
}
|
||||
if(alliance.get() == Alliance.Blue){
|
||||
y = 2.961328;
|
||||
y = 5;
|
||||
x = 1.11;
|
||||
angle = 0;
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 350 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 10){
|
||||
|
||||
@@ -14,6 +14,7 @@ import com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
@@ -52,46 +53,53 @@ public class GrimperReservoir extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
BotPose = limeLight3G.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
System.out.println(drivetrain.getPigeon2().getYaw().getValueAsDouble());
|
||||
if(angle < 0){
|
||||
angle = angle + 360;
|
||||
}
|
||||
if(alliance.get() == Alliance.Red){
|
||||
y = 6.959326;
|
||||
x = 13.57966;
|
||||
angle = 180;
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() < 190 && drivetrain.getPigeon2().getYaw().getValueAsDouble() > 170){
|
||||
drivetrain.setControl(drive.withVelocityY(y-boty).withVelocityX(x-botx));
|
||||
if(limeLight3G.getV()){
|
||||
|
||||
BotPose = limeLight3G.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
System.out.println(drivetrain.getPigeon2().getYaw().getValueAsDouble());
|
||||
if(angle < 0){
|
||||
angle = angle + 360;
|
||||
}
|
||||
if(alliance.get() == Alliance.Red){
|
||||
y = 6.959326;
|
||||
x = 13.57966;
|
||||
angle = 180;
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() < 190 && drivetrain.getPigeon2().getYaw().getValueAsDouble() > 170){
|
||||
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp(((y-boty)*5), -2, 2)).withVelocityX(MathUtil.clamp(((x-botx)*5),-2,2)));
|
||||
}
|
||||
else{
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(1));
|
||||
}
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-1));
|
||||
}
|
||||
}
|
||||
}
|
||||
else{
|
||||
y = 2.6;
|
||||
x = 1.11;
|
||||
angle = 0;
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 358 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 2){
|
||||
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp(((y-boty)*5), -2, 2)).withVelocityX(MathUtil.clamp(((x-botx)*5),-2,2)).withRotationalRate(0));
|
||||
}
|
||||
else{
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-1));
|
||||
System.out.println("x");
|
||||
}
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
System.out.println("e");
|
||||
drivetrain.setControl(drive.withRotationalRate(1));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5*180/Math.PI));
|
||||
}
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5*180/Math.PI));
|
||||
}
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||
}
|
||||
}
|
||||
else{
|
||||
y = 5.081328;
|
||||
x = 1.11;
|
||||
angle = 0;
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 350 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 10){
|
||||
drivetrain.setControl(drive.withVelocityY(y-boty).withVelocityX(x-botx));
|
||||
}
|
||||
else{
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5*180/Math.PI));
|
||||
}
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5*180/Math.PI));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@@ -103,6 +111,6 @@ public class GrimperReservoir extends Command {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return (y-boty < 0.05 && y-boty >-0.05) && (x-botx < 0.05 && x-botx > -0.05);
|
||||
return (y-boty < 0.1 && y-boty >-0.1) && (x-botx < 0.1 && x-botx > -0.1);
|
||||
}
|
||||
}
|
||||
@@ -85,8 +85,6 @@ public class LimelighterAuto extends Command {
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0));
|
||||
}
|
||||
drivetrain.setControl(
|
||||
drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
|
||||
System.out.println(angle);
|
||||
if (calcul < 0.2 && calcul > -0.2) {
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
|
||||
@@ -52,13 +52,18 @@ public class TournerVersReservoir extends Command {
|
||||
angle = 0;
|
||||
}
|
||||
}
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() < angle + 10){
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
else{
|
||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(-force*180/Math.PI));
|
||||
drivetrain.setControl(drive.withRotationalRate(-force*2));
|
||||
}
|
||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||
drivetrain.setControl(drive.withRotationalRate(force*180/Math.PI));
|
||||
drivetrain.setControl(drive.withRotationalRate(force*2));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
@@ -67,6 +72,6 @@ public class TournerVersReservoir extends Command {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return drivetrain.getPigeon2().getYaw().getValueAsDouble() > angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() < angle + 10;
|
||||
return drivetrain.getPigeon2().getYaw().getValueAsDouble() > angle && drivetrain.getPigeon2().getYaw().getValueAsDouble() < angle + 10;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -42,6 +42,6 @@ public class MonterGrimpeur extends Command {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return Math.abs(grimpeur.Position()) > grimpeur.PositionFinal();
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user