simulation
This commit is contained in:
@ -31,7 +31,7 @@ import frc.robot.subsystems.Pince;
|
||||
public class RobotContainer {
|
||||
|
||||
CommandXboxController manette1 = new CommandXboxController(0);
|
||||
CommandXboxController manette2 = new CommandXboxController(0);
|
||||
CommandXboxController manette2 = new CommandXboxController(1);
|
||||
private final SendableChooser<Command> autoChooser;
|
||||
Pince pince = new Pince();
|
||||
Elevateur elevateur = new Elevateur();
|
||||
|
@ -11,8 +11,8 @@ import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
public class Elevateur extends SubsystemBase {
|
||||
/** Creates a new Elevateur. */
|
||||
public Elevateur() {}
|
||||
final SparkMax monte = new SparkMax(0, MotorType.kBrushless);
|
||||
final DigitalInput limit2 = new DigitalInput(0);
|
||||
final SparkMax monte = new SparkMax(3, MotorType.kBrushless);
|
||||
final DigitalInput limit2 = new DigitalInput(1);
|
||||
public double position(){
|
||||
return monte.getEncoder().getPosition();
|
||||
}
|
||||
|
@ -11,8 +11,8 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
public class Grimpeur extends SubsystemBase {
|
||||
/** Creates a new Grimpeur. */
|
||||
public Grimpeur() {}
|
||||
final Spark grimpeur = new Spark(0);
|
||||
final DigitalInput limit1 = new DigitalInput(0);
|
||||
final Spark grimpeur = new Spark(2);
|
||||
final DigitalInput limit1 = new DigitalInput(3);
|
||||
public void grimpe(double vitesse){
|
||||
grimpeur.set(vitesse);
|
||||
}
|
||||
|
Reference in New Issue
Block a user