limelight+swerve=marche
This commit is contained in:
parent
590f9556c2
commit
b1e32bd6df
@ -78,16 +78,8 @@ public class RobotContainer {
|
|||||||
|
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
return
|
return new ParallelCommandGroup(
|
||||||
new
|
autoChooser.getSelected(),
|
||||||
ParallelCommandGroup(
|
new RainBow(bougie));
|
||||||
autoChooser
|
|
||||||
.getSelected(),
|
|
||||||
new
|
|
||||||
RainBow
|
|
||||||
(
|
|
||||||
bougie
|
|
||||||
)
|
|
||||||
);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -3,18 +3,32 @@
|
|||||||
// 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.commands;
|
package frc.robot.commands;
|
||||||
|
import static edu.wpi.first.units.Units.*;
|
||||||
|
|
||||||
|
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||||
|
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||||
|
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import frc.robot.TunerConstants.TunerConstants;
|
||||||
import frc.robot.subsystems.Limelight3;
|
import frc.robot.subsystems.Limelight3;
|
||||||
import frc.robot.subsystems.Limelight3G;
|
|
||||||
|
|
||||||
/* 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 */
|
/* 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 AprilTag3 extends Command {
|
public class AprilTag3 extends Command {
|
||||||
private Limelight3 limelight3;
|
private Limelight3 limelight3;
|
||||||
|
|
||||||
|
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||||
|
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
|
||||||
|
|
||||||
|
/* Setting up bindings for necessary control of the swerve drive platform */
|
||||||
|
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||||
|
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
|
||||||
|
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
|
||||||
/** Creates a new AprilTag3G. */
|
/** Creates a new AprilTag3G. */
|
||||||
public AprilTag3(Limelight3 limelight3) {
|
public AprilTag3(Limelight3 limelight3) {
|
||||||
this.limelight3 = limelight3;
|
this.limelight3 = limelight3;
|
||||||
addRequirements(limelight3);
|
addRequirements(limelight3);
|
||||||
|
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -27,17 +41,20 @@ public class AprilTag3 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(limelight3.getV() == true){
|
|
||||||
|
|
||||||
|
if(limelight3.getV() == true){
|
||||||
|
drive.withRotationalRate(limelight3.getX()/48);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
|
drive.withRotationalRate(0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {}
|
public void end(boolean interrupted) {
|
||||||
|
drive.withRotationalRate(0);
|
||||||
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
|
@ -3,13 +3,26 @@
|
|||||||
// 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.commands;
|
package frc.robot.commands;
|
||||||
|
import static edu.wpi.first.units.Units.*;
|
||||||
|
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||||
|
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import frc.robot.TunerConstants.TunerConstants;
|
||||||
|
|
||||||
import frc.robot.subsystems.Limelight3G;
|
import frc.robot.subsystems.Limelight3G;
|
||||||
|
|
||||||
/* 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 */
|
/* 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 AprilTag3G extends Command {
|
public class AprilTag3G extends Command {
|
||||||
private Limelight3G limelight3g;
|
private Limelight3G limelight3g;
|
||||||
|
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||||
|
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
|
||||||
|
|
||||||
|
/* Setting up bindings for necessary control of the swerve drive platform */
|
||||||
|
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||||
|
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
|
||||||
|
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
|
||||||
|
/** Creates a new AprilTag3G. */
|
||||||
/** Creates a new AprilTag3G. */
|
/** Creates a new AprilTag3G. */
|
||||||
public AprilTag3G(Limelight3G limelight3g) {
|
public AprilTag3G(Limelight3G limelight3g) {
|
||||||
this.limelight3g = limelight3g;
|
this.limelight3g = limelight3g;
|
||||||
@ -25,17 +38,17 @@ public class AprilTag3G extends Command {
|
|||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(limelight3g.getV() == true){
|
if(limelight3g.getV() == true){
|
||||||
|
drive.withRotationalRate(limelight3g.getX()/48);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
|
drive.withRotationalRate(0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {
|
public void end(boolean interrupted) {
|
||||||
|
drive.withRotationalRate(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
|
@ -3,17 +3,28 @@
|
|||||||
// 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.commands;
|
package frc.robot.commands;
|
||||||
|
import static edu.wpi.first.units.Units.*;
|
||||||
|
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||||
|
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import frc.robot.TunerConstants.TunerConstants;
|
||||||
import frc.robot.subsystems.Limelight3;
|
import frc.robot.subsystems.Limelight3;
|
||||||
import frc.robot.subsystems.Limelight3G;
|
|
||||||
|
|
||||||
/* 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 */
|
/* 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 Forme3 extends Command {
|
public class Forme3 extends Command {
|
||||||
private Limelight3 limelight3;
|
private Limelight3 limelight3;
|
||||||
|
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||||
|
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
|
||||||
|
|
||||||
|
/* Setting up bindings for necessary control of the swerve drive platform */
|
||||||
|
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||||
|
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
|
||||||
|
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
|
||||||
/** Creates a new Forme3. */
|
/** Creates a new Forme3. */
|
||||||
public Forme3(Limelight3 limelight3) {
|
public Forme3(Limelight3 limelight3) {
|
||||||
this.limelight3 = limelight3;
|
this.limelight3 = limelight3;
|
||||||
|
|
||||||
addRequirements(limelight3);
|
addRequirements(limelight3);
|
||||||
// Use addRequirements() here to declare subsystem dependencies.
|
// Use addRequirements() here to declare subsystem dependencies.
|
||||||
}
|
}
|
||||||
@ -28,16 +39,18 @@ public class Forme3 extends Command {
|
|||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
if(limelight3.getV() == true){
|
if(limelight3.getV() == true){
|
||||||
|
drive.withRotationalRate(limelight3.getX()/48);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
|
drive.withRotationalRate(0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Called once the command ends or is interrupted.
|
// Called once the command ends or is interrupted.
|
||||||
@Override
|
@Override
|
||||||
public void end(boolean interrupted) {}
|
public void end(boolean interrupted) {
|
||||||
|
drive.withRotationalRate(0);
|
||||||
|
}
|
||||||
|
|
||||||
// Returns true when the command should end.
|
// Returns true when the command should end.
|
||||||
@Override
|
@Override
|
||||||
|
Loading…
x
Reference in New Issue
Block a user