mirror of
https://github.com/Team4388/RiseOfRidgebotics2020.git
synced 2026-06-09 00:38:00 -06:00
Added comp paths
This commit is contained in:
@@ -39,9 +39,11 @@ import frc4388.robot.commands.auto.DriveOffLineForward;
|
||||
import frc4388.robot.commands.auto.EightBallAutoMiddle;
|
||||
import frc4388.robot.commands.auto.FiveBallAutoMiddle;
|
||||
import frc4388.robot.commands.auto.SixBallAutoMiddle;
|
||||
import frc4388.robot.commands.auto.Slalom;
|
||||
import frc4388.robot.commands.auto.TenBallAutoMiddle;
|
||||
import frc4388.robot.commands.InterruptSubystem;
|
||||
import frc4388.robot.commands.auto.AutoPath1FromCenter;
|
||||
import frc4388.robot.commands.auto.Barrel;
|
||||
import frc4388.robot.commands.auto.Wait;
|
||||
import frc4388.robot.commands.climber.DisengageRachet;
|
||||
import frc4388.robot.commands.climber.RunClimberWithTriggers;
|
||||
@@ -119,6 +121,10 @@ public class RobotContainer {
|
||||
|
||||
TenBallAutoMiddle m_tenBallAutoMiddle;
|
||||
|
||||
Slalom m_slalom;
|
||||
|
||||
Barrel m_barrel;
|
||||
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
@@ -177,7 +183,7 @@ public class RobotContainer {
|
||||
|
||||
// B driver test button
|
||||
new JoystickButton(getDriverJoystick(), XboxController.B_BUTTON)
|
||||
.whenPressed(new TurnDegrees(m_robotDrive, m_robotDrive.m_currentAngleYaw + 5));
|
||||
.whenPressed(new TurnDegrees(m_robotDrive, 45));
|
||||
// Y driver test button
|
||||
new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON)
|
||||
.whenPressed(new Wait(m_robotDrive, 0, 0));
|
||||
@@ -276,6 +282,18 @@ public class RobotContainer {
|
||||
|
||||
m_sixBallAutoMiddle = new SixBallAutoMiddle(m_robotDrive, buildPaths(sixBallAutoMiddlePaths));
|
||||
|
||||
String[] slalom = new String[]{
|
||||
"Slalom"
|
||||
};
|
||||
|
||||
m_slalom = new Slalom(m_robotDrive, buildPaths(slalom));
|
||||
|
||||
String[] barrel = new String[]{
|
||||
"Barrel"
|
||||
};
|
||||
|
||||
m_barrel = new Barrel(m_robotDrive, buildPaths(barrel));
|
||||
|
||||
String[] eightBallAutoMiddlePaths = new String[]{
|
||||
"EightBallMidComplete"
|
||||
};
|
||||
@@ -324,10 +342,12 @@ public class RobotContainer {
|
||||
|
||||
//return m_sixBallAutoMiddle.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
//return m_eightBallAutoMiddle.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
return m_driveOffLineForward.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
//return m_driveOffLineForward.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
//return m_driveOffLineBackward.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
//return m_fiveBallAutoMiddle.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
//return m_tenBallAutoMiddle.andThen(()-> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
//return m_slalom.andThen(()-> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
return m_barrel.andThen(()-> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
|
||||
} catch (Exception e) {
|
||||
System.err.println("ERROR");
|
||||
@@ -454,6 +474,7 @@ public class RobotContainer {
|
||||
return m_driverXbox;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Used for analog inputs like triggers and axises.
|
||||
* @return The IHandController interface for the Operator Controller.
|
||||
|
||||
@@ -0,0 +1,28 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 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.commands.auto;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.RamseteCommand;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
|
||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/latest/docs/software/commandbased/convenience-features.html
|
||||
public class Barrel extends SequentialCommandGroup {
|
||||
/**
|
||||
* Creates a new Barrel.
|
||||
*/
|
||||
public Barrel(Drive drive, RamseteCommand[] paths) {
|
||||
// Add your commands in the super() call, e.g.
|
||||
// super(new FooCommand(), new BarCommand());
|
||||
addCommands(
|
||||
paths[0]
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,28 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 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.commands.auto;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.RamseteCommand;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
|
||||
// NOTE: Consider using this command inline, rather than writing a subclass. For more
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/latest/docs/software/commandbased/convenience-features.html
|
||||
public class Slalom extends SequentialCommandGroup {
|
||||
/**
|
||||
* Creates a new Slalom.
|
||||
*/
|
||||
public Slalom(Drive drive, RamseteCommand[] paths) {
|
||||
// Add your commands in the super() call, e.g.
|
||||
// super(new FooCommand(), new BarCommand());
|
||||
addCommands(
|
||||
paths[0]
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -38,6 +38,7 @@ public class TurnDegrees extends CommandBase {
|
||||
public void initialize() {
|
||||
m_targetAngleTicksIn = (m_targetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV;
|
||||
m_currentYawInTicks = (m_drive.getGyroYaw() / 360) * DriveConstants.TICKS_PER_GYRO_REV;
|
||||
SmartDashboard.putNumber("Current Yaw Ticks", m_currentYawInTicks);
|
||||
m_targetAngleTicksOut = m_targetAngleTicksIn + m_currentYawInTicks;
|
||||
|
||||
i = 0;
|
||||
@@ -48,7 +49,7 @@ public class TurnDegrees extends CommandBase {
|
||||
public void execute() {
|
||||
m_currentYawInTicks = (m_drive.getGyroYaw() / 360) * DriveConstants.TICKS_PER_GYRO_REV;
|
||||
|
||||
m_drive.runTurningPID(m_targetAngleTicksOut);
|
||||
m_drive.runTurningPID(m_targetAngleTicksIn);
|
||||
|
||||
SmartDashboard.putNumber("Turning Error", Math.abs(m_currentYawInTicks - m_targetAngleTicksOut));
|
||||
SmartDashboard.putNumber("Turning Target", m_targetAngleTicksOut);
|
||||
|
||||
Reference in New Issue
Block a user