Merge branch 'requin' of https://git.demerso.net/PLS5618/Reefscape-2025
This commit is contained in:
commit
105447c4ad
63
src/main/java/frc/robot/commands/BalayeuseAlgue.java
Normal file
63
src/main/java/frc/robot/commands/BalayeuseAlgue.java
Normal file
@ -0,0 +1,63 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Bougie;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 BalayeuseAlgue extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
private Bougie bougie;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public BalayeuseAlgue(Requin requin, Bougie bougie) {
|
||||||
|
this.requin = requin;
|
||||||
|
this.bougie =bougie;
|
||||||
|
addRequirements(requin,bougie);
|
||||||
|
// 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() {
|
||||||
|
if(requin.encodeur()>=500 && requin.encodeur()<=510)
|
||||||
|
{
|
||||||
|
requin.rotationer(0);
|
||||||
|
if(requin.amp()> 60){
|
||||||
|
requin.balaye(0);
|
||||||
|
bougie.Vert();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
requin.balaye(0.5);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(requin.encodeur()>=510){
|
||||||
|
requin.rotationer(0.5);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(-0.5);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.rotationer(0);
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
40
src/main/java/frc/robot/commands/BalayeuseBas.java
Normal file
40
src/main/java/frc/robot/commands/BalayeuseBas.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.Command;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 BalayeuseBas extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public BalayeuseBas(Requin requin) {
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
|
// 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() {
|
||||||
|
requin.rotationer(-0.5);
|
||||||
|
}
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.rotationer(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
67
src/main/java/frc/robot/commands/BalayeuseCoral.java
Normal file
67
src/main/java/frc/robot/commands/BalayeuseCoral.java
Normal file
@ -0,0 +1,67 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Bougie;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 BalayeuseCoral extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
private Bougie bougie;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public BalayeuseCoral(Requin requin, Bougie bougie) {
|
||||||
|
this.requin = requin;
|
||||||
|
this.bougie = bougie;
|
||||||
|
addRequirements(requin,bougie);
|
||||||
|
// 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() {
|
||||||
|
if(requin.encodeur()>=100 && requin.encodeur()<=110){
|
||||||
|
requin.rotationer(0);
|
||||||
|
if(requin.amp()>60){
|
||||||
|
requin.balaye(0);
|
||||||
|
bougie.Vert();
|
||||||
|
if(requin.enHaut()){
|
||||||
|
requin.rotationer(0);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(0.5);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.balaye(0.5);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(requin.encodeur()>=110){
|
||||||
|
requin.rotationer(0.5);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(-0.5);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.rotationer(0);
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
47
src/main/java/frc/robot/commands/BalayeuseHaut.java
Normal file
47
src/main/java/frc/robot/commands/BalayeuseHaut.java
Normal file
@ -0,0 +1,47 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 BalayeuseHaut extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public BalayeuseHaut(Requin requin) {
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
|
// 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() {
|
||||||
|
if(requin.enHaut()==true){
|
||||||
|
requin.rotationer(0);
|
||||||
|
requin.reset();
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(-0.5);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.rotationer(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
41
src/main/java/frc/robot/commands/ExpireAlgue.java
Normal file
41
src/main/java/frc/robot/commands/ExpireAlgue.java
Normal file
@ -0,0 +1,41 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 ExpireAlgue extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
/** Creates a new ExpireAlgue. */
|
||||||
|
public ExpireAlgue(Requin requin) {
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
|
// 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() {
|
||||||
|
requin.balaye(0.5);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
65
src/main/java/frc/robot/commands/L1Requin.java
Normal file
65
src/main/java/frc/robot/commands/L1Requin.java
Normal file
@ -0,0 +1,65 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Bougie;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 L1Requin extends Command {
|
||||||
|
private Requin requin;
|
||||||
|
private Bougie bougie;
|
||||||
|
/** Creates a new Balayeuse. */
|
||||||
|
public L1Requin(Requin requin,Bougie bougie) {
|
||||||
|
this.requin = requin;
|
||||||
|
this.bougie = bougie;
|
||||||
|
addRequirements(requin,bougie);
|
||||||
|
// 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() {
|
||||||
|
|
||||||
|
if(requin.encodeur()>=800 && requin.encodeur()<=810){
|
||||||
|
requin.rotationer(0);
|
||||||
|
if(requin.amp()>8){
|
||||||
|
requin.balaye(-0.5);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.balaye(0);
|
||||||
|
bougie.Rouge();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(requin.encodeur()>=810){
|
||||||
|
requin.rotationer(0.5);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(-0.5);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.rotationer(0);
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
41
src/main/java/frc/robot/commands/aspire.java
Normal file
41
src/main/java/frc/robot/commands/aspire.java
Normal file
@ -0,0 +1,41 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 aspire extends Command {
|
||||||
|
/** Creates a new aspire. */
|
||||||
|
private Requin requin;
|
||||||
|
public aspire(Requin requin) {
|
||||||
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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() {
|
||||||
|
requin.balaye(0.3);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
41
src/main/java/frc/robot/commands/exspire.java
Normal file
41
src/main/java/frc/robot/commands/exspire.java
Normal file
@ -0,0 +1,41 @@
|
|||||||
|
// 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.Command;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 exspire extends Command {
|
||||||
|
/** Creates a new aspire. */
|
||||||
|
private Requin requin;
|
||||||
|
public exspire(Requin requin) {
|
||||||
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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() {
|
||||||
|
requin.balaye(-0.3);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.balaye(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
49
src/main/java/frc/robot/commands/requin_manuel.java
Normal file
49
src/main/java/frc/robot/commands/requin_manuel.java
Normal file
@ -0,0 +1,49 @@
|
|||||||
|
// 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 java.util.function.DoubleSupplier;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import frc.robot.subsystems.Requin;
|
||||||
|
|
||||||
|
/* 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 requin_manuel extends Command {
|
||||||
|
/** Creates a new requin_manuel. */
|
||||||
|
private Requin requin;
|
||||||
|
private DoubleSupplier x;
|
||||||
|
public requin_manuel(Requin requin) {
|
||||||
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
|
this.requin = requin;
|
||||||
|
addRequirements(requin);
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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() {
|
||||||
|
if(requin.enHaut()){
|
||||||
|
requin.rotationer(0);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
requin.rotationer(x.getAsDouble());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once the command ends or is interrupted.
|
||||||
|
@Override
|
||||||
|
public void end(boolean interrupted) {
|
||||||
|
requin.rotationer(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns true when the command should end.
|
||||||
|
@Override
|
||||||
|
public boolean isFinished() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
@ -43,8 +43,12 @@ public class Bougie extends SubsystemBase {
|
|||||||
candle.setLEDs(255, 215, 0,0,48,8);
|
candle.setLEDs(255, 215, 0,0,48,8);
|
||||||
candle.setLEDs(255, 215, 0,0,64,8);
|
candle.setLEDs(255, 215, 0,0,64,8);
|
||||||
}
|
}
|
||||||
public void RainBow(){candle.animate(rainbowAnim);}
|
public void RainBow(){
|
||||||
public void RainBowStop(){candle.animate(null);}
|
candle.animate(rainbowAnim);
|
||||||
|
}
|
||||||
|
public void RainBowStop(){
|
||||||
|
candle.animate(null);
|
||||||
|
}
|
||||||
@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
|
||||||
|
48
src/main/java/frc/robot/subsystems/Requin.java
Normal file
48
src/main/java/frc/robot/subsystems/Requin.java
Normal file
@ -0,0 +1,48 @@
|
|||||||
|
// 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.subsystems;
|
||||||
|
|
||||||
|
import com.revrobotics.spark.SparkFlex;
|
||||||
|
import com.revrobotics.spark.SparkMax;
|
||||||
|
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||||
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
|
public class Requin extends SubsystemBase {
|
||||||
|
/** Creates a new Requin. */
|
||||||
|
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||||
|
public Requin() {
|
||||||
|
teb.addBoolean("limit requin", this::enHaut);
|
||||||
|
}
|
||||||
|
|
||||||
|
final SparkFlex balaye = new SparkFlex(15, MotorType.kBrushless);
|
||||||
|
final SparkMax rotatione = new SparkMax(17, MotorType.kBrushless);
|
||||||
|
final DigitalInput limit3 = new DigitalInput(1);
|
||||||
|
|
||||||
|
public void balaye(double vitesse){
|
||||||
|
balaye.set(vitesse);
|
||||||
|
}
|
||||||
|
public void rotationer(double vitesse){
|
||||||
|
rotatione.set(vitesse);
|
||||||
|
}
|
||||||
|
public boolean enHaut(){
|
||||||
|
return limit3.get();
|
||||||
|
}
|
||||||
|
public double encodeur(){
|
||||||
|
return rotatione.getEncoder().getPosition();
|
||||||
|
}
|
||||||
|
public void reset(){
|
||||||
|
rotatione.getEncoder().setPosition(0);
|
||||||
|
}
|
||||||
|
public double amp(){
|
||||||
|
return balaye.getOutputCurrent();
|
||||||
|
}
|
||||||
|
@Override
|
||||||
|
public void periodic() {
|
||||||
|
// This method will be called once per scheduler run
|
||||||
|
}
|
||||||
|
}
|
Loading…
x
Reference in New Issue
Block a user