mirror of
https://github.com/Team4388/RiseOfRidgebotics2020.git
synced 2026-06-09 08:48:01 -06:00
did a lot
This commit is contained in:
@@ -19,6 +19,7 @@ import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.controller.RamseteController;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Transform2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj.trajectory.Trajectory;
|
||||
@@ -33,6 +34,8 @@ import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
import frc4388.robot.Constants.DriveConstants;
|
||||
import frc4388.robot.Constants.OIConstants;
|
||||
import frc4388.robot.commands.auto.DriveOffLineBackward;
|
||||
import frc4388.robot.commands.auto.DriveOffLineForward;
|
||||
import frc4388.robot.commands.auto.EightBallAutoMiddle;
|
||||
import frc4388.robot.commands.auto.SixBallAutoMiddle;
|
||||
import frc4388.robot.commands.auto.Wait;
|
||||
@@ -92,11 +95,16 @@ public class RobotContainer {
|
||||
private final XboxController m_operatorXbox = new XboxController(OIConstants.XBOX_OPERATOR_ID);
|
||||
|
||||
/* Autos */
|
||||
SixBallAutoMiddle m_sixBallAutoMiddle;
|
||||
double m_totalTimeAuto;
|
||||
|
||||
SixBallAutoMiddle m_sixBallAutoMiddle;
|
||||
|
||||
EightBallAutoMiddle m_eightBallAutoMiddle;
|
||||
|
||||
DriveOffLineForward m_driveOffLineForward;
|
||||
|
||||
DriveOffLineBackward m_driveOffLineBackward;
|
||||
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
@@ -247,12 +255,26 @@ public class RobotContainer {
|
||||
String[] sixBallAutoMiddlePaths = new String[]{
|
||||
"SixBallMidComplete"
|
||||
};
|
||||
m_sixBallAutoMiddle = new SixBallAutoMiddle(m_robotDrive, buildPaths(sixBallAutoMiddlePaths));
|
||||
|
||||
m_sixBallAutoMiddle = new SixBallAutoMiddle(m_robotDrive, buildPaths(sixBallAutoMiddlePaths, false));
|
||||
|
||||
String[] eightBallAutoMiddlePaths = new String[]{
|
||||
"EightBallMidComplete"
|
||||
};
|
||||
m_eightBallAutoMiddle = new EightBallAutoMiddle(m_robotDrive, buildPaths(eightBallAutoMiddlePaths));
|
||||
|
||||
m_eightBallAutoMiddle = new EightBallAutoMiddle(m_robotDrive, buildPaths(eightBallAutoMiddlePaths, false));
|
||||
|
||||
String[] driveOffLineForwardPaths = new String[]{
|
||||
"DriveOffLineForward"
|
||||
};
|
||||
|
||||
m_driveOffLineForward = new DriveOffLineForward(m_robotDrive, buildPaths(driveOffLineForwardPaths, false));
|
||||
|
||||
String[] driveOffLineBackwardPaths = new String[]{
|
||||
"DriveOffLineBackward"
|
||||
};
|
||||
|
||||
m_driveOffLineBackward = new DriveOffLineBackward(m_robotDrive, buildPaths(driveOffLineBackwardPaths, true));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -271,7 +293,9 @@ public class RobotContainer {
|
||||
SmartDashboard.putNumber("Trajectory Total Time", m_totalTimeAuto);
|
||||
|
||||
//return m_sixBallAutoMiddle.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
return m_eightBallAutoMiddle.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_driveOffLineBackward.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));
|
||||
|
||||
} catch (Exception e) {
|
||||
System.err.println("ERROR");
|
||||
@@ -314,7 +338,7 @@ public class RobotContainer {
|
||||
return ramseteCommand;
|
||||
}
|
||||
|
||||
public RamseteCommand[] buildPaths(String[] paths) {
|
||||
public RamseteCommand[] buildPaths(String[] paths, boolean isReversed) {
|
||||
RamseteCommand[] ramseteCommands = new RamseteCommand[paths.length];
|
||||
double[] times = new double[paths.length];
|
||||
Trajectory initialTrajectory;
|
||||
@@ -327,6 +351,7 @@ public class RobotContainer {
|
||||
Path trajectoryPath = Filesystem.getDeployDirectory().toPath().resolve(trajectoryJSON);
|
||||
Trajectory trajectory = TrajectoryUtil.fromPathweaverJson(trajectoryPath);
|
||||
initialTrajectory = trajectory;
|
||||
|
||||
RamseteCommand ramseteCommand = getRamseteCommand(trajectory.relativeTo(initialTrajectory.getInitialPose()));
|
||||
ramseteCommands[0] = ramseteCommand;
|
||||
times[0] = initialTrajectory.getTotalTimeSeconds();
|
||||
|
||||
@@ -0,0 +1,31 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import frc4388.robot.commands.drive.TurnDegrees;
|
||||
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 DriveOffLineBackward extends SequentialCommandGroup {
|
||||
/**
|
||||
* Creates a new DriveOffLineBackward.
|
||||
*/
|
||||
public DriveOffLineBackward(Drive drive, RamseteCommand[] paths) {
|
||||
// Add your commands in the super() call, e.g.
|
||||
// super(new FooCommand(), new BarCommand());
|
||||
|
||||
addCommands(
|
||||
new TankDriveVelocity(drive, -1, -1, 2)
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,29 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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 DriveOffLineForward extends SequentialCommandGroup {
|
||||
/**
|
||||
* Creates a new DriveOffLineForward.
|
||||
*/
|
||||
public DriveOffLineForward(Drive drive, RamseteCommand[] paths) {
|
||||
// Add your commands in the super() call, e.g.
|
||||
// super(new FooCommand(), new BarCommand());
|
||||
|
||||
addCommands(
|
||||
paths[0]
|
||||
);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,67 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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.CommandBase;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
|
||||
public class TankDriveVelocity extends CommandBase {
|
||||
Drive m_drive;
|
||||
double m_leftTargetVel;
|
||||
double m_rightTargetVel;
|
||||
|
||||
double m_targetTime;
|
||||
double m_firstTimeSec;
|
||||
double m_currentTimeSec;
|
||||
double m_diffSec;
|
||||
|
||||
/**
|
||||
* Creates a new TankDriveVelocity.
|
||||
*/
|
||||
public TankDriveVelocity(Drive subsystem, double leftTargetVel, double rightTargetVel, double targetTime) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_drive = subsystem;
|
||||
m_leftTargetVel = leftTargetVel;
|
||||
m_rightTargetVel = rightTargetVel;
|
||||
m_targetTime = targetTime;
|
||||
addRequirements(subsystem);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
m_firstTimeSec = (System.currentTimeMillis() / 1000);
|
||||
m_diffSec = 0;
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
m_currentTimeSec = (System.currentTimeMillis() / 1000);
|
||||
m_diffSec = m_currentTimeSec - m_firstTimeSec;
|
||||
|
||||
if (m_diffSec < m_targetTime) {
|
||||
m_drive.tankDriveVelocity(m_leftTargetVel, m_rightTargetVel);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
if (m_diffSec >= m_targetTime) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user