Grattedebug
This commit is contained in:
parent
d3e305c11a
commit
aa420b56af
@ -11,8 +11,8 @@ public class Constants {
|
|||||||
//moteur
|
//moteur
|
||||||
|
|
||||||
|
|
||||||
public static int GratteD = 7;
|
public static int GratteD = 8;
|
||||||
public static int GratteG = 8;
|
public static int GratteG = 7;
|
||||||
|
|
||||||
|
|
||||||
// pneumatique
|
// pneumatique
|
||||||
|
@ -114,9 +114,9 @@ public class RobotContainer {
|
|||||||
manette1.b().onTrue(brakeFerme);
|
manette1.b().onTrue(brakeFerme);
|
||||||
manette1.leftBumper().whileTrue(aprilTag);
|
manette1.leftBumper().whileTrue(aprilTag);
|
||||||
manette1.rightBumper().whileTrue(tape);
|
manette1.rightBumper().whileTrue(tape);
|
||||||
manette1.povUp().whileTrue(creerCommandBras(51, -40));
|
manette1.povUp().whileTrue(creerCommandBras(51, -37));
|
||||||
manette1.povDown().whileTrue(creerCommandBras(9, -14));
|
manette1.povDown().whileTrue(creerCommandBras(9, -12));
|
||||||
manette1.povRight().whileTrue(creerCommandBras(44, -17));
|
manette1.povRight().whileTrue(creerCommandBras(45, -13));
|
||||||
manette1.povLeft().whileTrue(creerCommandBras(0, 0));
|
manette1.povLeft().whileTrue(creerCommandBras(0, 0));
|
||||||
manette1.y().whileTrue(activerLimeLight);
|
manette1.y().whileTrue(activerLimeLight);
|
||||||
//manette 2
|
//manette 2
|
||||||
|
@ -28,7 +28,9 @@ public class ActiverLimeLight extends CommandBase {
|
|||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {}
|
public void end(boolean interrupted) {
|
||||||
|
limelight.joueurhumain1();
|
||||||
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
|
@ -20,23 +20,23 @@ public class GratteBaisser extends CommandBase {
|
|||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {
|
public void initialize() {
|
||||||
gratte.setenHaut(false);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// 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(gratte.basd()){
|
if(gratte.basd()){
|
||||||
gratte.baiserd(0);
|
gratte.bougerd(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
gratte.baiserd(0.5);
|
gratte.bougerd(0.3);
|
||||||
}
|
}
|
||||||
if(gratte.basg()){
|
if(gratte.basg()){
|
||||||
gratte.baiserg(0);
|
gratte.bougerg(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
gratte.baiserg(0.5);
|
gratte.bougerg(0.3);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -45,8 +45,8 @@ public class GratteBaisser extends CommandBase {
|
|||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
gratte.baiserd(0);
|
gratte.bougerd(0);
|
||||||
gratte.baiserg(0);
|
gratte.bougerg(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
|
@ -20,31 +20,30 @@ public class GratteMonte extends CommandBase {
|
|||||||
// Called when the command is initially scheduled.
|
// Called when the command is initially scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void initialize() {
|
public void initialize() {
|
||||||
gratte.setenHaut(true);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// 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(gratte.hautd()){
|
if(gratte.hautd()){
|
||||||
gratte.Leverd(0);
|
gratte.bougerd(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
gratte.Leverd(0.5);
|
gratte.bougerd(-0.3);
|
||||||
}
|
}
|
||||||
if(gratte.hautg()) {
|
if(gratte.hautg()) {
|
||||||
gratte.Leverg(0);
|
gratte.bougerg(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
gratte.Leverg(0.5);
|
gratte.bougerg(-0.3);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
gratte.Leverd(0);
|
gratte.bougerd(0);
|
||||||
gratte.Leverg(0);
|
gratte.bougerg(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
|
@ -18,8 +18,10 @@ public class DescendrePivotBras extends SequentialCommandGroup {
|
|||||||
// Add your commands in the addCommands() call, e.g.
|
// Add your commands in the addCommands() call, e.g.
|
||||||
// addCommands(new FooCommand(), new BarCommand());
|
// addCommands(new FooCommand(), new BarCommand());
|
||||||
addCommands(
|
addCommands(
|
||||||
|
|
||||||
new Bougerbras(brasTelescopique, distanceBras),
|
new Bougerbras(brasTelescopique, distanceBras),
|
||||||
new Bougerpivot(pivot, distancePivot)
|
new Bougerpivot(pivot, distancePivot)
|
||||||
|
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -4,7 +4,7 @@
|
|||||||
|
|
||||||
package frc.robot.commands.bras;
|
package frc.robot.commands.bras;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Commands;
|
|
||||||
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
||||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||||
@ -13,15 +13,17 @@ import frc.robot.subsystems.bras.Pivot;
|
|||||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||||
// information, see:
|
// information, see:
|
||||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||||
public class MonterPivotBras extends ParallelCommandGroup {
|
public class MonterPivotBras extends SequentialCommandGroup {
|
||||||
/** Creates a new Sequancepivotbras. */
|
/** Creates a new Sequancepivotbras. */
|
||||||
public MonterPivotBras(BrasTelescopique brasTelescopique, Pivot pivot, double distanceBras, double distancePivot) {
|
public MonterPivotBras(BrasTelescopique brasTelescopique, Pivot pivot, double distanceBras, double distancePivot) {
|
||||||
|
|
||||||
// Add your commands in the addCommands() call, e.g.
|
// Add your commands in the addCommands() call, e.g.
|
||||||
// addCommands(new FooCommand(), new BarCommand());
|
// addCommands(new FooCommand(), new BarCommand());
|
||||||
addCommands(
|
addCommands(
|
||||||
new SequentialCommandGroup(Commands.waitUntil(()->pivot.distance()>8),new Bougerbras(brasTelescopique, distanceBras)),
|
new Bougerpivot(pivot, 10).unless(()->pivot.distance()>10),
|
||||||
new Bougerpivot(pivot, distancePivot)
|
new ParallelCommandGroup(new Bougerpivot(pivot, distancePivot)),
|
||||||
|
new ParallelCommandGroup(new Bougerbras(brasTelescopique, distanceBras))
|
||||||
|
|
||||||
|
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
@ -29,11 +29,11 @@ public class PivoteBrasMilieux extends CommandBase {
|
|||||||
// 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(brasTelescopique.distance()>-12.5){
|
if(brasTelescopique.distance()>-11){
|
||||||
brasTelescopique.AvanceRecule(-0.15);
|
brasTelescopique.AvanceRecule(-0.15);
|
||||||
brasTelescopique.fermer();
|
brasTelescopique.fermer();
|
||||||
}
|
}
|
||||||
else if(brasTelescopique.distance()<-13.5) {
|
else if(brasTelescopique.distance()<-13) {
|
||||||
brasTelescopique.AvanceRecule(0.15);
|
brasTelescopique.AvanceRecule(0.15);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -24,15 +24,6 @@ ShuffleboardLayout limitswitchgratte = Shuffleboard.getTab("teb")
|
|||||||
private DigitalInput limithg = new DigitalInput(Constants.limithg);
|
private DigitalInput limithg = new DigitalInput(Constants.limithg);
|
||||||
private DigitalInput limitbd = new DigitalInput(Constants.limitbd);
|
private DigitalInput limitbd = new DigitalInput(Constants.limitbd);
|
||||||
private DigitalInput limitbg = new DigitalInput(Constants.limitbg);
|
private DigitalInput limitbg = new DigitalInput(Constants.limitbg);
|
||||||
public boolean baiser;
|
|
||||||
boolean enHaut = true;
|
|
||||||
public void setenHaut(boolean enHaut){
|
|
||||||
this.enHaut = enHaut;
|
|
||||||
}
|
|
||||||
public boolean getenHaut(){
|
|
||||||
return enHaut;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
public boolean hautd(){
|
public boolean hautd(){
|
||||||
return limithd.get();
|
return limithd.get();
|
||||||
@ -55,17 +46,11 @@ ShuffleboardLayout limitswitchgratte = Shuffleboard.getTab("teb")
|
|||||||
limitswitchgratte.addBoolean ("limithd", this::hautd);
|
limitswitchgratte.addBoolean ("limithd", this::hautd);
|
||||||
limitswitchgratte.addBoolean ("limitbg", this::basg);
|
limitswitchgratte.addBoolean ("limitbg", this::basg);
|
||||||
}
|
}
|
||||||
public void Leverd(double vitesse){
|
public void bougerd(double vitesse){
|
||||||
Gratted.set(-vitesse);
|
Gratted.set(vitesse);
|
||||||
|
|
||||||
}
|
}
|
||||||
public void Leverg(double vitesse){
|
public void bougerg(double vitesse){
|
||||||
Gratteg.set(-vitesse);
|
|
||||||
}
|
|
||||||
public void baiserd(double vitesse){
|
|
||||||
Gratted.set(vitesse);
|
|
||||||
}
|
|
||||||
public void baiserg(double vitesse){
|
|
||||||
Gratteg.set(vitesse);
|
Gratteg.set(vitesse);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -47,7 +47,7 @@ public class Limelight extends SubsystemBase {
|
|||||||
public double getYaw() {
|
public double getYaw() {
|
||||||
var result = limelight.getLatestResult();
|
var result = limelight.getLatestResult();
|
||||||
if(result.hasTargets()){
|
if(result.hasTargets()){
|
||||||
return -result.getBestTarget().getYaw()/60;
|
return -result.getBestTarget().getYaw()/30;
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
@ -57,6 +57,9 @@ public class Limelight extends SubsystemBase {
|
|||||||
limelight.setDriverMode(true);
|
limelight.setDriverMode(true);
|
||||||
}
|
}
|
||||||
public void joueurhumain(){
|
public void joueurhumain(){
|
||||||
|
limelight.setLED(VisionLEDMode.kOn);
|
||||||
|
}
|
||||||
|
public void joueurhumain1(){
|
||||||
limelight.setLED(VisionLEDMode.kOff);
|
limelight.setLED(VisionLEDMode.kOff);
|
||||||
}
|
}
|
||||||
@Override
|
@Override
|
||||||
|
Loading…
x
Reference in New Issue
Block a user