limelight pls marche
This commit is contained in:
@@ -53,46 +53,63 @@ public class Limelighter extends Command {
|
||||
double[] BotPose = new double[6];
|
||||
System.out.println("e");
|
||||
if (limelight3g.getV()) {
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
// BotPose = limelight3g.getBotPoseBlue();
|
||||
if (!alliance.isPresent()) {
|
||||
return;
|
||||
}
|
||||
if (alliance.get() == Alliance.Blue) {
|
||||
x = 4.6;
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
}
|
||||
else {
|
||||
x = 11.915394;
|
||||
BotPose = limelight3g.getBotPoseRed();
|
||||
}
|
||||
botx = BotPose[1];
|
||||
boty = BotPose[0];
|
||||
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||
if(calcul < -5 && calcul > -180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
if(angle > 180){
|
||||
angle -= 360;
|
||||
}
|
||||
else if(calcul > 5 && calcul < 180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
if(calcul > -5 && calcul < 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0));
|
||||
}
|
||||
else if(calcul >= 180){
|
||||
else if(calcul > 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
}
|
||||
else if(calcul <= -180){
|
||||
else if(calcul < -5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
}
|
||||
else{
|
||||
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));
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
}
|
||||
// if(calcul < -5 && calcul > -180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul > 5 && calcul < 180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul >= 180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul <= -180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else{
|
||||
// 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));
|
||||
// }
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
|
||||
@@ -53,46 +53,63 @@ public class LimelighterAuto extends Command {
|
||||
double[] BotPose = new double[6];
|
||||
System.out.println("e");
|
||||
if (limelight3g.getV()) {
|
||||
if (!alliance.isPresent()) {
|
||||
// BotPose = limelight3g.getBotPoseBlue();
|
||||
if (!alliance.isPresent()) {
|
||||
return;
|
||||
}
|
||||
if (alliance.get() == Alliance.Blue) {
|
||||
x = 4.6;
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
}
|
||||
else {
|
||||
x = 11.915394;
|
||||
BotPose = limelight3g.getBotPoseRed();
|
||||
}
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
botx = BotPose[1];
|
||||
boty = BotPose[0];
|
||||
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||
calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||
if(calcul < -5 && calcul > -180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
if(angle > 180){
|
||||
angle -= 360;
|
||||
}
|
||||
else if(calcul > 5 && calcul < 180){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
if(calcul > -5 && calcul < 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0));
|
||||
}
|
||||
else if(calcul >= 180){
|
||||
else if(calcul > 5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
}
|
||||
else if(calcul <= -180){
|
||||
else if(calcul < -5){
|
||||
drivetrain.setControl(
|
||||
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
}
|
||||
else{
|
||||
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));
|
||||
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
}
|
||||
// if(calcul < -5 && calcul > -180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul > 5 && calcul < 180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul >= 180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else if(calcul <= -180){
|
||||
// drivetrain.setControl(
|
||||
// drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||
// }
|
||||
// else{
|
||||
// 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));
|
||||
// }
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
@@ -109,7 +126,6 @@ public class LimelighterAuto extends Command {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return calcul < 5 && calcul > -5;
|
||||
return calcul > -5 && calcul < 5;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -52,22 +52,28 @@ NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag")
|
||||
}
|
||||
public double Calcule(double x1, double x2, double y1, double y2, double angle)
|
||||
{
|
||||
if(x1 > x2){
|
||||
if(y1 > y2){
|
||||
return Math.atan(90-((x2 - x1) / (y2 - y1))) * (180 / Math.PI) - angle;
|
||||
// if(x1 > x2){
|
||||
// if(y1 > y2){
|
||||
// return Math.atan(90-((x2 - x1) / (y2 - y1))) * (180 / Math.PI) - angle;
|
||||
// }
|
||||
// else{
|
||||
// return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI)+90 - angle;
|
||||
// }
|
||||
// }
|
||||
// else{
|
||||
// if(y1 > y2){
|
||||
// return Math.atan((x2 - x1) / (y2 - y1))* (180 / Math.PI)+270 - angle;
|
||||
// }
|
||||
// else{
|
||||
// return Math.atan(90-((x2 - x1) / (y2 - y1))) * (180 / Math.PI)+180 - angle;
|
||||
// }
|
||||
// }
|
||||
if(y1 > y2){
|
||||
return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI) - angle;
|
||||
}
|
||||
else{
|
||||
return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI)+90 - angle;
|
||||
return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI)-360 - angle;
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(y1 > y2){
|
||||
return Math.atan((x2 - x1) / (y2 - y1))* (180 / Math.PI)+270 - angle;
|
||||
}
|
||||
else{
|
||||
return Math.atan(90-((x2 - x1) / (y2 - y1))) * (180 / Math.PI)+180 - angle;
|
||||
}
|
||||
}
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
|
||||
Reference in New Issue
Block a user