mirror of
https://github.com/Team4388/2023WayOfTheRobot.git
synced 2026-06-09 00:37:59 -06:00
186 lines
6.7 KiB
Java
186 lines
6.7 KiB
Java
/*----------------------------------------------------------------------------*/
|
|
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
|
|
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
|
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
|
/* the project. */
|
|
/*----------------------------------------------------------------------------*/
|
|
|
|
package frc4388.robot;
|
|
|
|
import com.ctre.phoenix.motorcontrol.ControlMode;
|
|
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
|
import com.ctre.phoenix.sensors.WPI_Pigeon2;
|
|
|
|
import edu.wpi.first.math.MathUtil;
|
|
import edu.wpi.first.math.filter.SlewRateLimiter;
|
|
import edu.wpi.first.math.util.Units;
|
|
import edu.wpi.first.wpilibj.TimedRobot;
|
|
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
|
import edu.wpi.first.wpilibj2.command.Command;
|
|
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
|
import frc4388.robot.Constants.SwerveDriveConstants;
|
|
import frc4388.robot.commands.AutoBalance;
|
|
import frc4388.utility.RobotGyro;
|
|
import frc4388.utility.RobotTime;
|
|
|
|
/**
|
|
* The VM is configured to automatically run this class, and to call the
|
|
* functions corresponding to each mode, as described in the TimedRobot
|
|
* documentation. If you change the name of this class or the package after
|
|
* creating this project, you must also update the build.gradle file in the
|
|
* project.
|
|
*/
|
|
public class Robot extends TimedRobot {
|
|
Command m_autonomousCommand;
|
|
|
|
private RobotTime m_robotTime = RobotTime.getInstance();
|
|
private RobotContainer m_robotContainer;
|
|
|
|
public static class MicroBot extends SubsystemBase {
|
|
public WPI_Pigeon2 pigeon = new WPI_Pigeon2(14);
|
|
public RobotGyro gyro = new RobotGyro(pigeon);
|
|
|
|
public TalonSRX frontLeft = new TalonSRX(2);
|
|
public TalonSRX backLeft = new TalonSRX(3);
|
|
public TalonSRX backRight = new TalonSRX(5);
|
|
public TalonSRX frontRight = new TalonSRX(4);
|
|
|
|
public MicroBot() {
|
|
frontRight.configFactoryDefault();
|
|
frontLeft.configFactoryDefault();
|
|
backLeft.configFactoryDefault();
|
|
backRight.configFactoryDefault();
|
|
|
|
frontLeft.setInverted(true);
|
|
backLeft.setInverted(true);
|
|
}
|
|
|
|
public void setOutput(double output) {
|
|
frontRight.set(ControlMode.PercentOutput, output);
|
|
frontLeft.set(ControlMode.PercentOutput, output);
|
|
backLeft.set(ControlMode.PercentOutput, output);
|
|
backRight.set(ControlMode.PercentOutput, output);
|
|
}
|
|
}
|
|
|
|
private final SlewRateLimiter xLimiter = new SlewRateLimiter(3);
|
|
private final SlewRateLimiter yLimiter = new SlewRateLimiter(3);
|
|
private final SlewRateLimiter rotLimiter = new SlewRateLimiter(3);
|
|
|
|
// private MicroBot bot = new MicroBot();
|
|
|
|
/**
|
|
* This function is run when the robot is first started up and should be
|
|
* used for any initialization code.
|
|
*/
|
|
@Override
|
|
public void robotInit() {
|
|
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
|
|
// autonomous chooser on the dashboard.
|
|
m_robotContainer = new RobotContainer();
|
|
|
|
// bot.setDefaultCommand(new AutoBalance(bot));
|
|
}
|
|
|
|
/**
|
|
* This function is called every robot packet, no matter the mode. Use
|
|
* this for items like diagnostics that you want ran during disabled,
|
|
* autonomous, teleoperated and test.
|
|
*
|
|
* <p>This runs after the mode specific periodic functions, but before
|
|
* LiveWindow and SmartDashboard integrated updating.
|
|
*/
|
|
@Override
|
|
public void robotPeriodic() {
|
|
m_robotTime.updateTimes();
|
|
// Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
|
|
// commands, running already-scheduled commands, removing finished or interrupted commands,
|
|
// and running subsystem periodic() methods. This must be called from the robot's periodic
|
|
// block in order for anything in the Command-based framework to work.
|
|
CommandScheduler.getInstance().run();
|
|
}
|
|
|
|
/**
|
|
* This function is called once each time the robot enters Disabled mode.
|
|
* You can use it to reset any subsystem information you want to clear when
|
|
* the robot is disabled.
|
|
*/
|
|
@Override
|
|
public void disabledInit() {
|
|
m_robotTime.endMatchTime();
|
|
}
|
|
|
|
@Override
|
|
public void disabledPeriodic() {
|
|
}
|
|
|
|
/**
|
|
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
|
|
*/
|
|
@Override
|
|
public void autonomousInit() {
|
|
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
|
|
|
/*
|
|
* String autoSelected = SmartDashboard.getString("Auto Selector",
|
|
* "Default"); switch(autoSelected) { case "My Auto": autonomousCommand
|
|
* = new MyAutoCommand(); break; case "Default Auto": default:
|
|
* autonomousCommand = new ExampleCommand(); break; }
|
|
*/
|
|
|
|
// schedule the autonomous command (example)
|
|
if (m_autonomousCommand != null) {
|
|
m_autonomousCommand.schedule();
|
|
}
|
|
m_robotTime.startMatchTime();
|
|
}
|
|
|
|
/**
|
|
* This function is called periodically during autonomous.
|
|
*/
|
|
@Override
|
|
public void autonomousPeriodic() {
|
|
}
|
|
|
|
@Override
|
|
public void teleopInit() {
|
|
// This makes sure that the autonomous stops running when
|
|
// teleop starts running. If you want the autonomous to
|
|
// continue until interrupted by another command, remove
|
|
// this line or comment it out.
|
|
if (m_autonomousCommand != null) {
|
|
m_autonomousCommand.cancel();
|
|
}
|
|
m_robotTime.startMatchTime();
|
|
|
|
// m_robotContainer.gyroRef.reset();
|
|
}
|
|
|
|
/**
|
|
* This function is called periodically during operator control.
|
|
*/
|
|
@Override
|
|
public void teleopPeriodic() {
|
|
// SmartDashboard.putNumber("yaw", m_robotContainer.gyroRef.getAngle());
|
|
// SmartDashboard.putNumber("pitch", m_robotContainer.gyroRef.getPitch());
|
|
// SmartDashboard.putNumber("roll", m_robotContainer.gyroRef.getRoll());
|
|
this.drive(false);
|
|
}
|
|
|
|
private void drive(boolean fieldRelative) {
|
|
final double xSpeed = -xLimiter.calculate(MathUtil.applyDeadband(m_robotContainer.getDriverController().getLeftXAxis() * -0.3, 0.02) * Units.feetToMeters(SwerveDriveConstants.MAX_SPEED_FEET_PER_SECOND));
|
|
final double ySpeed = -yLimiter.calculate(MathUtil.applyDeadband(m_robotContainer.getDriverController().getLeftYAxis() * 0.3, 0.02) * Units.feetToMeters(SwerveDriveConstants.MAX_SPEED_FEET_PER_SECOND));
|
|
final double rot = -rotLimiter.calculate(MathUtil.applyDeadband(m_robotContainer.getDriverController().getRightXAxis() * 0.3, 0.02) * Units.feetToMeters(Math.PI));
|
|
|
|
m_robotContainer.m_robotSwerveDrive.drive(xSpeed, ySpeed, rot, fieldRelative);
|
|
}
|
|
|
|
/**
|
|
* This function is called periodically during test mode.
|
|
*/
|
|
@Override
|
|
public void testPeriodic() {
|
|
}
|
|
}
|