Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
commit
df4d981230
@ -42,12 +42,17 @@ public class Constants {
|
|||||||
public static int ArriereDroit = 6;
|
public static int ArriereDroit = 6;
|
||||||
public static int ArriereGauche = 7;
|
public static int ArriereGauche = 7;
|
||||||
|
|
||||||
// Limit switsh
|
// Limit switch
|
||||||
public static int guideurhaut = 23;
|
public static int guideurhaut = 23;
|
||||||
public static int guideurbas = 24;
|
public static int guideurbas = 24;
|
||||||
public static int limitacc = 25;
|
public static int limitacc = 25;
|
||||||
public static int limitacc2 = 76;
|
public static int limitacc2 = 76;
|
||||||
public static int limithaut = 28;
|
public static int limithaut = 28;
|
||||||
public static int limitbas = 29;
|
public static int limitbas = 29;
|
||||||
|
|
||||||
|
//piston
|
||||||
|
public static int pistondroiteouvre= 30;
|
||||||
|
public static int pistondroiteferme= 31;
|
||||||
|
public static int pistondgaucheouvre= 32;
|
||||||
|
public static int pistondgauchferme= 32;
|
||||||
}
|
}
|
||||||
|
38
src/main/java/frc/robot/command/GrimpeurHaut.java
Normal file
38
src/main/java/frc/robot/command/GrimpeurHaut.java
Normal file
@ -0,0 +1,38 @@
|
|||||||
|
// 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.command;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import frc.robot.subsystem.Grimpeur;
|
||||||
|
|
||||||
|
public class GrimpeurHaut extends Command {
|
||||||
|
private Grimpeur grimpeur;
|
||||||
|
/** Creates a new GrimpeurHaut. */
|
||||||
|
public GrimpeurHaut(Grimpeur grimpeur) {
|
||||||
|
this.grimpeur = grimpeur;
|
||||||
|
addRequirements(grimpeur);
|
||||||
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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() {
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
@ -9,6 +9,9 @@ import com.revrobotics.CANSparkMax;
|
|||||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
|
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||||
|
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||||
|
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
import frc.robot.Constants;
|
import frc.robot.Constants;
|
||||||
|
|
||||||
@ -21,6 +24,8 @@ public class Grimpeur extends SubsystemBase {
|
|||||||
// limit switch
|
// limit switch
|
||||||
final DigitalInput limitdroite = new DigitalInput(Constants.limithaut);
|
final DigitalInput limitdroite = new DigitalInput(Constants.limithaut);
|
||||||
final DigitalInput limitgauche = new DigitalInput(Constants.limitbas);
|
final DigitalInput limitgauche = new DigitalInput(Constants.limitbas);
|
||||||
|
final DoubleSolenoid pistondroite= new DoubleSolenoid(PneumaticsModuleType.CTREPCM, Constants.pistondroiteouvre, Constants.pistondroiteouvre);
|
||||||
|
final DoubleSolenoid pistondgauche= new DoubleSolenoid(PneumaticsModuleType.CTREPCM, Constants.pistondgaucheouvre, Constants.pistondroiteouvre);
|
||||||
//fonction
|
//fonction
|
||||||
public void droit(double vitesse){
|
public void droit(double vitesse){
|
||||||
grimpeurd.set(vitesse);
|
grimpeurd.set(vitesse);
|
||||||
@ -40,10 +45,19 @@ public void resetencodeurd(){
|
|||||||
public void resetencodeurg(){
|
public void resetencodeurg(){
|
||||||
grimpeurg.getEncoder().setPosition(0);
|
grimpeurg.getEncoder().setPosition(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
public AHRS gyroscope = new AHRS();
|
public AHRS gyroscope = new AHRS();
|
||||||
public double getpitch(){
|
public double getpitch(){
|
||||||
return gyroscope.getPitch();
|
return gyroscope.getPitch();
|
||||||
}
|
}
|
||||||
|
public void pistonouvre(){
|
||||||
|
pistondroite.set(Value.kForward);
|
||||||
|
pistondgauche.set(Value.kForward);
|
||||||
|
}
|
||||||
|
public void pistonferme(){
|
||||||
|
pistondroite.set(Value.kReverse);
|
||||||
|
pistondgauche.set(Value.kReverse);
|
||||||
|
}
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
// This method will be called once per scheduler run
|
// This method will be called once per scheduler run
|
||||||
|
Loading…
x
Reference in New Issue
Block a user