Merge branch 'main' of https://demerso.net/pls5618/2023/robot
This commit is contained in:
40
src/main/java/frc/robot/commands/ActiverLimeLight.java
Normal file
40
src/main/java/frc/robot/commands/ActiverLimeLight.java
Normal file
@ -0,0 +1,40 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.Limelight;
|
||||
|
||||
public class ActiverLimeLight extends CommandBase {
|
||||
private Limelight limelight;
|
||||
/** Creates a new ActiverLimeLight. */
|
||||
public ActiverLimeLight(Limelight limelight) {
|
||||
this.limelight = limelight;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
addRequirements(limelight);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
limelight.joueurhumain();
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
limelight.joueurhumain1();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
@ -32,7 +32,7 @@ public class Apriltag extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw());
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw(),false);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -7,9 +7,6 @@ package frc.robot.commands;
|
||||
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.BasePilotable;
|
||||
|
||||
@ -33,12 +30,14 @@ public class Avancer extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
basePilotable.drive(0.3,0);
|
||||
basePilotable.drive(0.4,0);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
basePilotable.drive(0,0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
|
@ -3,6 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.Gratte;
|
||||
|
||||
@ -19,23 +20,23 @@ public class GratteBaisser extends CommandBase {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
gratte.setenHaut(false);
|
||||
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(gratte.basd()){
|
||||
gratte.baiserd(0);
|
||||
gratte.bougerd(0);
|
||||
}
|
||||
else{
|
||||
gratte.baiserd(0.5);
|
||||
gratte.bougerd(0.3);
|
||||
}
|
||||
if(gratte.basg()){
|
||||
gratte.baiserg(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
else{
|
||||
gratte.baiserg(0.5);
|
||||
gratte.bougerg(0.3);
|
||||
}
|
||||
|
||||
|
||||
@ -44,8 +45,8 @@ public class GratteBaisser extends CommandBase {
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
gratte.baiserd(0);
|
||||
gratte.baiserg(0);
|
||||
gratte.bougerd(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
@ -21,31 +21,30 @@ public class GratteMonte extends CommandBase {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
gratte.setenHaut(true);
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(gratte.hautd()){
|
||||
gratte.Leverd(0);
|
||||
gratte.bougerd(0);
|
||||
}
|
||||
else{
|
||||
gratte.Leverd(0.5);
|
||||
gratte.bougerd(-0.3);
|
||||
}
|
||||
if(gratte.hautg()) {
|
||||
gratte.Leverg(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
else{
|
||||
gratte.Leverg(0.5);
|
||||
gratte.bougerg(-0.3);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
gratte.Leverd(0);
|
||||
gratte.Leverg(0);
|
||||
gratte.bougerd(0);
|
||||
gratte.bougerg(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
@ -26,11 +26,11 @@ public class Gyro extends CommandBase {
|
||||
public void execute() {
|
||||
if(basePilotable.getpitch()>6)
|
||||
{
|
||||
basePilotable.drive(0.3*basePilotable.getpitch()/12, 0);
|
||||
basePilotable.drive(0.4*basePilotable.getpitch()/12, 0);
|
||||
}
|
||||
else if(basePilotable.getpitch()<-6)
|
||||
{
|
||||
basePilotable.drive(0.3*basePilotable.getpitch()/12, 0);
|
||||
basePilotable.drive(0.4*basePilotable.getpitch()/12, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -35,7 +35,9 @@ public class Reculer extends CommandBase {
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
basePilotable.drive(0,0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
|
@ -32,7 +32,7 @@ public class Tape extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw());
|
||||
basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw(),false);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -6,45 +6,36 @@ package frc.robot.commands.bras;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||
import frc.robot.subsystems.bras.Pivot;
|
||||
|
||||
public class PivotChercheHaut extends CommandBase {
|
||||
private BrasTelescopique brasTelescopique;
|
||||
private Pivot pivot;
|
||||
/** Creates a new PivotChercheHaut. */
|
||||
public PivotChercheHaut(BrasTelescopique brasTelescopique, Pivot pivot) {
|
||||
public class Bougerbras extends CommandBase {
|
||||
/** Creates a new bougerbras. */
|
||||
double distance;
|
||||
BrasTelescopique brasTelescopique;
|
||||
public Bougerbras(BrasTelescopique brasTelescopique,double distance) {
|
||||
this.brasTelescopique = brasTelescopique;
|
||||
this.pivot = pivot;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
this.distance = distance;
|
||||
addRequirements(brasTelescopique);
|
||||
addRequirements(pivot);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
brasTelescopique.fermer();
|
||||
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.photocell()){
|
||||
brasTelescopique.ouvrir();
|
||||
brasTelescopique.Reset();
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
else{
|
||||
if(brasTelescopique.distance()>distance+0.5 ) {
|
||||
brasTelescopique.AvanceRecule(-0.3);
|
||||
|
||||
}
|
||||
else if(brasTelescopique.distance()<distance-0.5) {
|
||||
brasTelescopique.AvanceRecule(0.3);
|
||||
}
|
||||
if (pivot.distance()<43.5){
|
||||
pivot.monteDescendre(0.5);
|
||||
}
|
||||
else if(pivot.distance()>44.5) {
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
}
|
||||
|
||||
@ -52,13 +43,13 @@ public class PivotChercheHaut extends CommandBase {
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
pivot.monteDescendre(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return brasTelescopique.distance()>distance-0.5 && brasTelescopique.distance()<distance+0.5;
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -5,58 +5,47 @@
|
||||
package frc.robot.commands.bras;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||
import frc.robot.subsystems.bras.Pivot;
|
||||
|
||||
public class PivotBrasRentre extends CommandBase {
|
||||
private BrasTelescopique brasTelescopique;
|
||||
private Pivot pivot;
|
||||
/** Creates a new PivotBrasRentre. */
|
||||
public PivotBrasRentre(BrasTelescopique brasTelescopique, Pivot pivot) {
|
||||
this.brasTelescopique = brasTelescopique;
|
||||
public class Bougerpivot extends CommandBase {
|
||||
/** Creates a new Bougerpivot. */
|
||||
Pivot pivot;
|
||||
double distance;
|
||||
public Bougerpivot(Pivot pivot,double distance) {
|
||||
this.pivot = pivot;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
addRequirements(brasTelescopique);
|
||||
this.distance = distance;
|
||||
addRequirements(pivot);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.photocell()){
|
||||
brasTelescopique.ouvrir();
|
||||
brasTelescopique.Reset();
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
else{
|
||||
brasTelescopique.AvanceRecule(0.5);
|
||||
}
|
||||
if(pivot.limitpivot()){
|
||||
pivot.Reset();
|
||||
pivot.monteDescendre(0);
|
||||
}
|
||||
else{
|
||||
if(pivot.distance()>distance+0.5 ) {
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
else if(pivot.distance()<distance-0.5) {
|
||||
pivot.monteDescendre(0.5);
|
||||
}
|
||||
else {
|
||||
pivot.monteDescendre(0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
pivot.monteDescendre(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return brasTelescopique.photocell() && pivot.limitpivot();
|
||||
}
|
||||
return pivot.distance()>distance-0.5 && pivot.distance()<distance+0.5;
|
||||
|
||||
}
|
||||
}
|
@ -29,10 +29,12 @@ public class BrasManuel extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(doubleSupplier.getAsDouble()>0.2 && doubleSupplier.getAsDouble()<-0.2){
|
||||
brasTelescopique.AvanceRecule(doubleSupplier.getAsDouble());
|
||||
if(doubleSupplier.getAsDouble()>0.2 || doubleSupplier.getAsDouble()<-0.2){
|
||||
brasTelescopique.AvanceRecule(doubleSupplier.getAsDouble()*0.5);
|
||||
}
|
||||
|
||||
else{
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
|
@ -0,0 +1,27 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.commands.bras;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||
import frc.robot.subsystems.bras.Pivot;
|
||||
|
||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class DescendrePivotBras extends SequentialCommandGroup {
|
||||
/** Creates a new DescendrePivotBras. */
|
||||
public DescendrePivotBras(BrasTelescopique brasTelescopique, Pivot pivot, double distanceBras, double distancePivot) {
|
||||
// Add your commands in the addCommands() call, e.g.
|
||||
// addCommands(new FooCommand(), new BarCommand());
|
||||
addCommands(
|
||||
|
||||
new Bougerbras(brasTelescopique, distanceBras),
|
||||
new Bougerpivot(pivot, distancePivot)
|
||||
|
||||
);
|
||||
}
|
||||
}
|
30
src/main/java/frc/robot/commands/bras/MonterPivotBras.java
Normal file
30
src/main/java/frc/robot/commands/bras/MonterPivotBras.java
Normal file
@ -0,0 +1,30 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.commands.bras;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||
import frc.robot.subsystems.bras.Pivot;
|
||||
|
||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class MonterPivotBras extends SequentialCommandGroup {
|
||||
/** Creates a new Sequancepivotbras. */
|
||||
public MonterPivotBras(BrasTelescopique brasTelescopique, Pivot pivot, double distanceBras, double distancePivot) {
|
||||
|
||||
// Add your commands in the addCommands() call, e.g.
|
||||
// addCommands(new FooCommand(), new BarCommand());
|
||||
addCommands(
|
||||
new Bougerpivot(pivot, 10).unless(()->pivot.distance()>10),
|
||||
new ParallelCommandGroup(new Bougerpivot(pivot, distancePivot)),
|
||||
new ParallelCommandGroup(new Bougerbras(brasTelescopique, distanceBras))
|
||||
|
||||
|
||||
);
|
||||
}
|
||||
}
|
@ -1,67 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.commands.bras;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc.robot.subsystems.bras.BrasTelescopique;
|
||||
import frc.robot.subsystems.bras.Pivot;
|
||||
|
||||
public class PivotChercheBas extends CommandBase {
|
||||
private BrasTelescopique brasTelescopique;
|
||||
private Pivot pivot;
|
||||
/** Creates a new PivotChercheBas. */
|
||||
public PivotChercheBas(BrasTelescopique brasTelescopique, Pivot pivot) {
|
||||
this.brasTelescopique = brasTelescopique;
|
||||
this.pivot = pivot;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
addRequirements(brasTelescopique);
|
||||
addRequirements(pivot);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-17.5){
|
||||
brasTelescopique.AvanceRecule(-0.2);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-19.5) {
|
||||
brasTelescopique.AvanceRecule(0.2);
|
||||
}
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<8.5){
|
||||
pivot.monteDescendre(0.3);
|
||||
}
|
||||
else if(pivot.distance()>10.5) {
|
||||
pivot.monteDescendre(-0.3);
|
||||
}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
pivot.monteDescendre(0);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
@ -27,10 +27,14 @@ public class PivotManuel extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(doubleSupplier.getAsDouble()>0.2 && doubleSupplier.getAsDouble()<-0.2){
|
||||
pivot.monteDescendre(doubleSupplier.getAsDouble());}
|
||||
if(doubleSupplier.getAsDouble()>0.2 || doubleSupplier.getAsDouble()<-0.2){
|
||||
pivot.monteDescendre(-doubleSupplier.getAsDouble()*0.5)
|
||||
;}
|
||||
else{
|
||||
pivot.monteDescendre(0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
|
@ -31,21 +31,21 @@ public class PivoteBrasBas extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-13.5){
|
||||
if(brasTelescopique.distance()>-8.5){
|
||||
brasTelescopique.AvanceRecule(-0.2);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-15.5) {
|
||||
else if(brasTelescopique.distance()<-9.5) {
|
||||
brasTelescopique.AvanceRecule(0.2);
|
||||
}
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<8.5){
|
||||
if (pivot.distance()<12.5){
|
||||
pivot.monteDescendre(0.4);
|
||||
}
|
||||
else if(pivot.distance()>10.5) {
|
||||
else if(pivot.distance()>13.5) {
|
||||
pivot.monteDescendre(-0.4);
|
||||
}
|
||||
else{
|
||||
|
@ -29,21 +29,21 @@ public class PivoteBrasHaut extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-39.5){
|
||||
if(brasTelescopique.distance()>-36.5){
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-41.5) {
|
||||
else if(brasTelescopique.distance()<-37.5) {
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
}
|
||||
else {
|
||||
brasTelescopique.AvanceRecule(0);
|
||||
brasTelescopique.ouvrir();
|
||||
}
|
||||
if (pivot.distance()<50.5){
|
||||
if (pivot.distance()<52.5){
|
||||
pivot.monteDescendre(0.5);
|
||||
}
|
||||
else if(pivot.distance()>52.5) {
|
||||
else if(pivot.distance()>53.5) {
|
||||
pivot.monteDescendre(-0.5);
|
||||
}
|
||||
else{
|
||||
|
@ -29,11 +29,11 @@ public class PivoteBrasMilieux extends CommandBase {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(brasTelescopique.distance()>-16.5){
|
||||
if(brasTelescopique.distance()>-11){
|
||||
brasTelescopique.AvanceRecule(-0.15);
|
||||
brasTelescopique.fermer();
|
||||
}
|
||||
else if(brasTelescopique.distance()<-17.5) {
|
||||
else if(brasTelescopique.distance()<-13) {
|
||||
brasTelescopique.AvanceRecule(0.15);
|
||||
}
|
||||
else {
|
||||
|
Reference in New Issue
Block a user