Compare commits
6 Commits
coaching
...
ae9a6bd046
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
ae9a6bd046 | ||
|
|
10b0110315 | ||
| 098f16665a | |||
| 1240160ed7 | |||
| 4068016d36 | |||
|
|
6afc342006 |
@@ -0,0 +1,99 @@
|
|||||||
|
{
|
||||||
|
"version": "2025.0",
|
||||||
|
"command": {
|
||||||
|
"type": "sequential",
|
||||||
|
"data": {
|
||||||
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "DescendreBalayeuse"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "deadline",
|
||||||
|
"data": {
|
||||||
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "wait",
|
||||||
|
"data": {
|
||||||
|
"waitTime": 3.0
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "path",
|
||||||
|
"data": {
|
||||||
|
"pathName": "Depot"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "Aspirer"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "path",
|
||||||
|
"data": {
|
||||||
|
"pathName": "Tir"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "deadline",
|
||||||
|
"data": {
|
||||||
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "Lancer"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "Aspirer"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "path",
|
||||||
|
"data": {
|
||||||
|
"pathName": "GrimperReservoir"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "GrimperReservoir"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "MonterGrimpeur"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "path",
|
||||||
|
"data": {
|
||||||
|
"pathName": "MonterReservoir"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "DescendreGrimpeur"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"resetOdom": true,
|
||||||
|
"folder": null,
|
||||||
|
"choreoAuto": false
|
||||||
|
}
|
||||||
@@ -14,6 +14,12 @@
|
|||||||
"type": "deadline",
|
"type": "deadline",
|
||||||
"data": {
|
"data": {
|
||||||
"commands": [
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "wait",
|
||||||
|
"data": {
|
||||||
|
"waitTime": 3.0
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"type": "path",
|
"type": "path",
|
||||||
"data": {
|
"data": {
|
||||||
|
|||||||
@@ -14,6 +14,12 @@
|
|||||||
"type": "deadline",
|
"type": "deadline",
|
||||||
"data": {
|
"data": {
|
||||||
"commands": [
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "wait",
|
||||||
|
"data": {
|
||||||
|
"waitTime": 3.0
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"type": "path",
|
"type": "path",
|
||||||
"data": {
|
"data": {
|
||||||
|
|||||||
@@ -3,25 +3,25 @@
|
|||||||
"waypoints": [
|
"waypoints": [
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 1.0502282453637657,
|
"x": 1.0,
|
||||||
"y": 2.4758915834522113
|
"y": 2.6
|
||||||
},
|
},
|
||||||
"prevControl": null,
|
"prevControl": null,
|
||||||
"nextControl": {
|
"nextControl": {
|
||||||
"x": 1.0408884389937225,
|
"x": 0.9906601936299568,
|
||||||
"y": 2.742159765250622
|
"y": 2.866268181798411
|
||||||
},
|
},
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
"linkedName": null
|
"linkedName": null
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 1.0502282453637657,
|
"x": 1.0,
|
||||||
"y": 2.7734807417974334
|
"y": 2.9
|
||||||
},
|
},
|
||||||
"prevControl": {
|
"prevControl": {
|
||||||
"x": 1.0547546338516156,
|
"x": 1.00452638848785,
|
||||||
"y": 2.523521721541598
|
"y": 2.6500409797441646
|
||||||
},
|
},
|
||||||
"nextControl": null,
|
"nextControl": null,
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
|
|||||||
@@ -126,6 +126,7 @@ public class RobotContainer {
|
|||||||
manette1.b().whileTrue(new ModeOposer(lanceur));
|
manette1.b().whileTrue(new ModeOposer(lanceur));
|
||||||
manette1.a().whileTrue(new ModeOposerDemeleur(lanceur));
|
manette1.a().whileTrue(new ModeOposerDemeleur(lanceur));
|
||||||
manette1.y().whileTrue(new ModeOposerBalayeuse(balayeuse));
|
manette1.y().whileTrue(new ModeOposerBalayeuse(balayeuse));
|
||||||
|
manette1.povUp().whileTrue(new LancerAuto(lanceur, limeLight3G));
|
||||||
}
|
}
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
|
|||||||
@@ -40,6 +40,7 @@ public class Lancer extends Command {
|
|||||||
if(limeLight3G.getV()){}
|
if(limeLight3G.getV()){}
|
||||||
pidController = new PIDController(0.0007, 0,0, 0.001);
|
pidController = new PIDController(0.0007, 0,0, 0.001);
|
||||||
timer.reset();
|
timer.reset();
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
|
|||||||
@@ -27,6 +27,7 @@ public class Limelighter extends Command {
|
|||||||
double boty;
|
double boty;
|
||||||
double angle;
|
double angle;
|
||||||
double calcul;
|
double calcul;
|
||||||
|
double x;
|
||||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||||
@@ -42,7 +43,9 @@ public class Limelighter extends Command {
|
|||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
@@ -50,27 +53,37 @@ public class Limelighter extends Command {
|
|||||||
double[] BotPose = new double[6];
|
double[] BotPose = new double[6];
|
||||||
System.out.println("e");
|
System.out.println("e");
|
||||||
if (limelight3g.getV()) {
|
if (limelight3g.getV()) {
|
||||||
|
// BotPose = limelight3g.getBotPoseBlue();
|
||||||
|
if (!alliance.isPresent()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (alliance.get() == Alliance.Blue) {
|
||||||
|
x = 4.6;
|
||||||
BotPose = limelight3g.getBotPoseBlue();
|
BotPose = limelight3g.getBotPoseBlue();
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
x = 11.915394;
|
||||||
|
BotPose = limelight3g.getBotPoseRed();
|
||||||
|
}
|
||||||
botx = BotPose[1];
|
botx = BotPose[1];
|
||||||
boty = BotPose[0];
|
boty = BotPose[0];
|
||||||
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||||
calcul = limelight3g.Calcule(botx, 4, boty, 4.6, angle);
|
calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||||
if(calcul < -5 && calcul > -180){
|
if(calcul < -5 && calcul > -180){
|
||||||
drivetrain.setControl(
|
drivetrain.setControl(
|
||||||
drive.withRotationalRate(0.5*180/Math.PI));
|
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||||
}
|
}
|
||||||
else if(calcul > 5 && calcul < 180){
|
else if(calcul > 5 && calcul < 180){
|
||||||
drivetrain.setControl(
|
drivetrain.setControl(
|
||||||
drive.withRotationalRate(-0.5*180/Math.PI));
|
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||||
}
|
}
|
||||||
else if(calcul >= 180){
|
else if(calcul < -5){
|
||||||
drivetrain.setControl(
|
drivetrain.setControl(
|
||||||
drive.withRotationalRate(-0.5*180/Math.PI));
|
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||||
}
|
}
|
||||||
else if(calcul <= -180){
|
else if(calcul <= -180){
|
||||||
drivetrain.setControl(
|
drivetrain.setControl(
|
||||||
drive.withRotationalRate(0.5*180/Math.PI));
|
drive.withRotationalRate(0.5*(2*Math.PI)));
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
drivetrain.setControl(
|
drivetrain.setControl(
|
||||||
|
|||||||
@@ -47,7 +47,9 @@ public class GrimperMur extends Command {
|
|||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
@@ -60,7 +62,7 @@ public class GrimperMur extends Command {
|
|||||||
angle = angle + 360;
|
angle = angle + 360;
|
||||||
}
|
}
|
||||||
if(alliance.get() == Alliance.Blue){
|
if(alliance.get() == Alliance.Blue){
|
||||||
y = 2.961328;
|
y = 5;
|
||||||
x = 1.11;
|
x = 1.11;
|
||||||
angle = 0;
|
angle = 0;
|
||||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 350 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 10){
|
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.SwerveModule.DriveRequestType;
|
||||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||||
|
|
||||||
|
import edu.wpi.first.math.MathUtil;
|
||||||
import edu.wpi.first.wpilibj.DriverStation;
|
import edu.wpi.first.wpilibj.DriverStation;
|
||||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
@@ -47,11 +48,15 @@ public class GrimperReservoir extends Command {
|
|||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
|
if(limeLight3G.getV()){
|
||||||
|
|
||||||
BotPose = limeLight3G.getBotPoseBlue();
|
BotPose = limeLight3G.getBotPoseBlue();
|
||||||
botx = BotPose[0];
|
botx = BotPose[0];
|
||||||
boty = BotPose[1];
|
boty = BotPose[1];
|
||||||
@@ -64,34 +69,39 @@ public class GrimperReservoir extends Command {
|
|||||||
x = 13.57966;
|
x = 13.57966;
|
||||||
angle = 180;
|
angle = 180;
|
||||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() < 190 && drivetrain.getPigeon2().getYaw().getValueAsDouble() > 170){
|
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() < 190 && drivetrain.getPigeon2().getYaw().getValueAsDouble() > 170){
|
||||||
drivetrain.setControl(drive.withVelocityY(y-boty).withVelocityX(x-botx));
|
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp(((y-boty)*5), -2, 2)).withVelocityX(MathUtil.clamp(((x-botx)*5),-2,2)));
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||||
drivetrain.setControl(drive.withRotationalRate(0.5*180/Math.PI));
|
drivetrain.setControl(drive.withRotationalRate(1));
|
||||||
}
|
}
|
||||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||||
drivetrain.setControl(drive.withRotationalRate(-0.5*180/Math.PI));
|
drivetrain.setControl(drive.withRotationalRate(-1));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
y = 5.081328;
|
y = 2.6;
|
||||||
x = 1.11;
|
x = 1.11;
|
||||||
angle = 0;
|
angle = 0;
|
||||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 350 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 10){
|
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() > 358 || drivetrain.getPigeon2().getYaw().getValueAsDouble() < 2){
|
||||||
drivetrain.setControl(drive.withVelocityY(y-boty).withVelocityX(x-botx));
|
drivetrain.setControl(drive.withVelocityY(MathUtil.clamp(((y-boty)*5), -2, 2)).withVelocityX(MathUtil.clamp(((x-botx)*5),-2,2)).withRotationalRate(0));
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >0 && drivetrain.getPigeon2().getYaw().getValueAsDouble() <180){
|
||||||
drivetrain.setControl(drive.withRotationalRate(-0.5*180/Math.PI));
|
drivetrain.setControl(drive.withRotationalRate(-1));
|
||||||
|
System.out.println("x");
|
||||||
}
|
}
|
||||||
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||||
drivetrain.setControl(drive.withRotationalRate(0.5*180/Math.PI));
|
System.out.println("e");
|
||||||
|
drivetrain.setControl(drive.withRotationalRate(1));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@@ -103,6 +113,6 @@ public class GrimperReservoir extends Command {
|
|||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
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);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -38,6 +38,7 @@ public class LancerAuto extends Command {
|
|||||||
public void initialize() {
|
public void initialize() {
|
||||||
pidController = new PIDController(0.0007, 0, 0, 0.001);
|
pidController = new PIDController(0.0007, 0, 0, 0.001);
|
||||||
timer.reset();
|
timer.reset();
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
|
|||||||
@@ -27,6 +27,7 @@ public class LimelighterAuto extends Command {
|
|||||||
double boty;
|
double boty;
|
||||||
double angle;
|
double angle;
|
||||||
double calcul;
|
double calcul;
|
||||||
|
double x;
|
||||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||||
@@ -42,7 +43,9 @@ public class LimelighterAuto extends Command {
|
|||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
@@ -50,38 +53,63 @@ public class LimelighterAuto extends Command {
|
|||||||
double[] BotPose = new double[6];
|
double[] BotPose = new double[6];
|
||||||
System.out.println("e");
|
System.out.println("e");
|
||||||
if (limelight3g.getV()) {
|
if (limelight3g.getV()) {
|
||||||
|
// BotPose = limelight3g.getBotPoseBlue();
|
||||||
|
if (!alliance.isPresent()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (alliance.get() == Alliance.Blue) {
|
||||||
|
x = 4.6;
|
||||||
BotPose = limelight3g.getBotPoseBlue();
|
BotPose = limelight3g.getBotPoseBlue();
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
x = 11.915394;
|
||||||
|
BotPose = limelight3g.getBotPoseRed();
|
||||||
|
}
|
||||||
botx = BotPose[1];
|
botx = BotPose[1];
|
||||||
boty = BotPose[0];
|
boty = BotPose[0];
|
||||||
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
|
||||||
calcul = limelight3g.Calcule(botx, 4, boty, 4.6, angle);
|
calcul = limelight3g.Calcule(botx, x, boty, 4, angle);
|
||||||
if(calcul < -5 && calcul > -180){
|
if(angle > 180){
|
||||||
drivetrain.setControl(
|
angle -= 360;
|
||||||
drive.withRotationalRate(0.5*180/Math.PI));
|
|
||||||
}
|
}
|
||||||
else if(calcul > 5 && calcul < 180){
|
if(calcul > -5 && calcul < 5){
|
||||||
drivetrain.setControl(
|
|
||||||
drive.withRotationalRate(-0.5*180/Math.PI));
|
|
||||||
}
|
|
||||||
else if(calcul >= 180){
|
|
||||||
drivetrain.setControl(
|
|
||||||
drive.withRotationalRate(-0.5*180/Math.PI));
|
|
||||||
}
|
|
||||||
else if(calcul <= -180){
|
|
||||||
drivetrain.setControl(
|
|
||||||
drive.withRotationalRate(0.5*180/Math.PI));
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
drivetrain.setControl(
|
drivetrain.setControl(
|
||||||
drive.withRotationalRate(0));
|
drive.withRotationalRate(0));
|
||||||
}
|
}
|
||||||
|
else if(calcul > 5){
|
||||||
drivetrain.setControl(
|
drivetrain.setControl(
|
||||||
drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
|
drive.withRotationalRate(-0.5*(2*Math.PI)));
|
||||||
System.out.println(angle);
|
|
||||||
if (calcul < 0.2 && calcul > -0.2) {
|
|
||||||
drivetrain.setControl(drive.withRotationalRate(0));
|
|
||||||
}
|
}
|
||||||
|
else if(calcul < -5){
|
||||||
|
drivetrain.setControl(
|
||||||
|
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{
|
else{
|
||||||
drivetrain.setControl(drive.withRotationalRate(0));
|
drivetrain.setControl(drive.withRotationalRate(0));
|
||||||
@@ -98,7 +126,6 @@ public class LimelighterAuto extends Command {
|
|||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return calcul < 5 && calcul > -5;
|
return calcul > -5 && calcul < 5;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -37,7 +37,9 @@ public class TournerVersMur extends Command {
|
|||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
|
|||||||
@@ -37,7 +37,9 @@ public class TournerVersReservoir extends Command {
|
|||||||
|
|
||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {}
|
public void initialize() {
|
||||||
|
alliance = DriverStation.getAlliance();
|
||||||
|
}
|
||||||
|
|
||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
@@ -52,11 +54,16 @@ public class TournerVersReservoir extends Command {
|
|||||||
angle = 0;
|
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){
|
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){
|
else if(drivetrain.getPigeon2().getYaw().getValueAsDouble() >180){
|
||||||
drivetrain.setControl(drive.withRotationalRate(force*180/Math.PI));
|
drivetrain.setControl(drive.withRotationalRate(force*2));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -42,6 +42,6 @@ public class MonterGrimpeur extends Command {
|
|||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
public boolean isFinished() {
|
public boolean isFinished() {
|
||||||
return false;
|
return Math.abs(grimpeur.Position()) > grimpeur.PositionFinal();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -52,21 +52,27 @@ NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-tag")
|
|||||||
}
|
}
|
||||||
public double Calcule(double x1, double x2, double y1, double y2, double angle)
|
public double Calcule(double x1, double x2, double y1, double y2, double angle)
|
||||||
{
|
{
|
||||||
if(x1 > x2){
|
// 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){
|
if(y1 > y2){
|
||||||
return Math.atan(90-((x2 - x1) / (y2 - y1))) * (180 / Math.PI) - angle;
|
return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI) - angle;
|
||||||
}
|
}
|
||||||
else{
|
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(90-((x2 - x1) / (y2 - y1)))* (180 / Math.PI)+270 - angle;
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
return Math.atan((x2 - x1) / (y2 - y1)) * (180 / Math.PI)+180 - angle;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@Override
|
@Override
|
||||||
|
|||||||
Reference in New Issue
Block a user