Limit swich elevateur + limit switch pince (testé en simulation-Fonctionne)
This commit is contained in:
parent
d7a887571a
commit
280270245e
@ -133,7 +133,7 @@ public class RobotContainer {
|
|||||||
|
|
||||||
//Pince manuel
|
//Pince manuel
|
||||||
pince.setDefaultCommand(new RunCommand(()->{
|
pince.setDefaultCommand(new RunCommand(()->{
|
||||||
pince.pivote(MathUtil.applyDeadband(manette2.getRightY(), 0.1));
|
pince.pivote(MathUtil.applyDeadband(manette2.getRightY()*manette2.getRightY()*manette2.getRightY(), 0.05));
|
||||||
}, pince));
|
}, pince));
|
||||||
|
|
||||||
//Elevateur manuel
|
//Elevateur manuel
|
||||||
|
@ -28,7 +28,10 @@ public class ElevateurManuel extends Command {
|
|||||||
// 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 (elevateur.limit2())
|
if (elevateur.limit2()){
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
elevateur.vitesse(doubleSupplier.getAsDouble()/3.5);
|
elevateur.vitesse(doubleSupplier.getAsDouble()/3.5);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,41 +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.Pince;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
|
||||||
import frc.robot.subsystems.Pince;
|
|
||||||
|
|
||||||
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
|
|
||||||
public class Algue1Test extends Command {
|
|
||||||
private Pince pince;
|
|
||||||
/** Creates a new AlgueTest. */
|
|
||||||
public Algue1Test(Pince pince) {
|
|
||||||
this.pince = pince;
|
|
||||||
addRequirements(pince);
|
|
||||||
// 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() {
|
|
||||||
pince.algue1Test(0.2);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
|
||||||
@Override
|
|
||||||
public void end(boolean interrupted) {
|
|
||||||
pince.algue1Test(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
|
||||||
@Override
|
|
||||||
public boolean isFinished() {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
@ -1,41 +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.Pince;
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
|
||||||
import frc.robot.subsystems.Pince;
|
|
||||||
|
|
||||||
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
|
|
||||||
public class Algue2Test extends Command {
|
|
||||||
private Pince pince;
|
|
||||||
/** Creates a new AlgueTest. */
|
|
||||||
public Algue2Test(Pince pince) {
|
|
||||||
this.pince = pince;
|
|
||||||
addRequirements(pince);
|
|
||||||
// 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() {
|
|
||||||
pince.algue2Test(0.2);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
|
||||||
@Override
|
|
||||||
public void end(boolean interrupted) {
|
|
||||||
pince.algue2Test(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Returns true when the command should end.
|
|
||||||
@Override
|
|
||||||
public boolean isFinished() {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
@ -3,8 +3,6 @@
|
|||||||
// the WPILib BSD license file in the root directory of this project.
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
package frc.robot.subsystems;
|
package frc.robot.subsystems;
|
||||||
|
|
||||||
import edu.wpi.first.networktables.GenericEntry;
|
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
@ -25,7 +23,17 @@ public class Elevateur extends SubsystemBase {
|
|||||||
return monte.getEncoder().getPosition();
|
return monte.getEncoder().getPosition();
|
||||||
}
|
}
|
||||||
public void vitesse(double vitesse){
|
public void vitesse(double vitesse){
|
||||||
monte.set(vitesse);
|
if (limit2()) {
|
||||||
|
if (vitesse > 0) {
|
||||||
|
monte.set(0);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
monte.set(vitesse);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
monte.set(vitesse);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
public boolean limit2(){
|
public boolean limit2(){
|
||||||
return limit2.get();
|
return limit2.get();
|
||||||
|
@ -6,8 +6,6 @@ package frc.robot.subsystems;
|
|||||||
|
|
||||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||||
import com.revrobotics.spark.SparkMax;
|
import com.revrobotics.spark.SparkMax;
|
||||||
|
|
||||||
import edu.wpi.first.networktables.GenericEntry;
|
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
@ -27,11 +25,21 @@ public class Pince extends SubsystemBase {
|
|||||||
final DigitalInput limit6 = new DigitalInput(9);
|
final DigitalInput limit6 = new DigitalInput(9);
|
||||||
|
|
||||||
|
|
||||||
public void aspirecoral(double vitesse){
|
public void aspirecoral(double vitesse){
|
||||||
coral.set(vitesse);
|
coral.set(vitesse);
|
||||||
}
|
}
|
||||||
public void pivote(double vitesse){
|
public void pivote(double vitesse){
|
||||||
pivoti.set(vitesse);
|
if (position()) {
|
||||||
|
if (vitesse > 0) {
|
||||||
|
pivoti.set(0);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
pivoti.set(vitesse);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
pivoti.set(vitesse);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
public void aspirealgue(double vitesse){
|
public void aspirealgue(double vitesse){
|
||||||
algue2.set(-vitesse);
|
algue2.set(-vitesse);
|
||||||
@ -52,12 +60,7 @@ public double emperagecoral(){
|
|||||||
public double emperagealgue(){
|
public double emperagealgue(){
|
||||||
return algue1.getOutputCurrent();
|
return algue1.getOutputCurrent();
|
||||||
}
|
}
|
||||||
public void algue1Test(double vitesse){
|
|
||||||
algue1.set(vitesse);
|
|
||||||
}
|
|
||||||
public void algue2Test(double vitesse){
|
|
||||||
algue2.set(vitesse);
|
|
||||||
}
|
|
||||||
@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