mirror of
https://github.com/Team4388/2022NoWayHome.git
synced 2026-06-09 00:38:05 -06:00
THIS WORKS CURRENTLY
This commit is contained in:
@@ -64,9 +64,6 @@ public class Robot extends TimedRobot {
|
|||||||
LOGGER.log(Level.FINE, "Logging Test 6/8");
|
LOGGER.log(Level.FINE, "Logging Test 6/8");
|
||||||
LOGGER.log(Level.FINER, "Logging Test 7/8");
|
LOGGER.log(Level.FINER, "Logging Test 7/8");
|
||||||
LOGGER.log(Level.FINEST, "Logging Test 8/8");
|
LOGGER.log(Level.FINEST, "Logging Test 8/8");
|
||||||
Errors.log().run(() -> {
|
|
||||||
throw new Throwable("Exception Test");
|
|
||||||
});
|
|
||||||
|
|
||||||
// var path =
|
// var path =
|
||||||
// PathPlannerUtil.Path.read(Filesystem.getDeployDirectory().toPath().resolve("pathplanner").resolve("Move
|
// PathPlannerUtil.Path.read(Filesystem.getDeployDirectory().toPath().resolve("pathplanner").resolve("Move
|
||||||
|
|||||||
@@ -64,6 +64,7 @@ import frc4388.robot.subsystems.VisionOdometry;
|
|||||||
import frc4388.utility.PathPlannerUtil;
|
import frc4388.utility.PathPlannerUtil;
|
||||||
import frc4388.utility.controller.ButtonBox;
|
import frc4388.utility.controller.ButtonBox;
|
||||||
import frc4388.utility.controller.DeadbandedRawXboxController;
|
import frc4388.utility.controller.DeadbandedRawXboxController;
|
||||||
|
import frc4388.utility.controller.DeadbandedXboxController;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* This class is where the bulk of the robot should be declared. Since
|
* This class is where the bulk of the robot should be declared. Since
|
||||||
@@ -96,8 +97,8 @@ public class RobotContainer {
|
|||||||
/* Autonomous */
|
/* Autonomous */
|
||||||
private final PathRecorder m_pathChooser = new PathRecorder(m_robotSwerveDrive);
|
private final PathRecorder m_pathChooser = new PathRecorder(m_robotSwerveDrive);
|
||||||
// Controllers
|
// Controllers
|
||||||
private final static XboxController m_driverXbox = new DeadbandedRawXboxController(OIConstants.XBOX_DRIVER_ID);
|
private final static XboxController m_driverXbox = new DeadbandedXboxController(OIConstants.XBOX_DRIVER_ID);
|
||||||
private final static XboxController m_operatorXbox = new DeadbandedRawXboxController(OIConstants.XBOX_OPERATOR_ID);
|
private final static XboxController m_operatorXbox = new DeadbandedXboxController(OIConstants.XBOX_OPERATOR_ID);
|
||||||
private final ButtonBox m_buttonBox = new ButtonBox(OIConstants.BUTTON_BOX_ID);
|
private final ButtonBox m_buttonBox = new ButtonBox(OIConstants.BUTTON_BOX_ID);
|
||||||
|
|
||||||
public static boolean softLimits = true;
|
public static boolean softLimits = true;
|
||||||
|
|||||||
@@ -79,15 +79,14 @@ public class TrackTarget extends CommandBase {
|
|||||||
|
|
||||||
velocity = 0;
|
velocity = 0;
|
||||||
hoodPosition = 0;
|
hoodPosition = 0;
|
||||||
|
m_visionOdometry.setDriverMode(false);
|
||||||
|
m_visionOdometry.setLEDs(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
// 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() {
|
||||||
try {
|
try {
|
||||||
m_visionOdometry.setDriverMode(false);
|
|
||||||
m_visionOdometry.setLEDs(true);
|
|
||||||
|
|
||||||
points = m_visionOdometry.getTargetPoints();
|
points = m_visionOdometry.getTargetPoints();
|
||||||
// points = getFakePoints();
|
// points = getFakePoints();
|
||||||
//// points = filterPoints(points);
|
//// points = filterPoints(points);
|
||||||
@@ -114,8 +113,8 @@ public class TrackTarget extends CommandBase {
|
|||||||
velocity = m_boomBoom.getVelocity(regressedDistance);
|
velocity = m_boomBoom.getVelocity(regressedDistance);
|
||||||
hoodPosition = m_boomBoom.getHood(regressedDistance);
|
hoodPosition = m_boomBoom.getHood(regressedDistance);
|
||||||
|
|
||||||
m_boomBoom.runDrumShooterVelocityPID(velocity);
|
m_boomBoom.runDrumShooterVelocityPID(velocity + 20);
|
||||||
m_hood.runAngleAdjustPID(hoodPosition);
|
m_hood.runAngleAdjustPID(hoodPosition + 20);
|
||||||
|
|
||||||
double currentDrumVel = this.m_boomBoom.m_shooterFalconLeft.getSelectedSensorVelocity();
|
double currentDrumVel = this.m_boomBoom.m_shooterFalconLeft.getSelectedSensorVelocity();
|
||||||
double currentHood = this.m_hood.getEncoderPosition();
|
double currentHood = this.m_hood.getEncoderPosition();
|
||||||
|
|||||||
@@ -30,12 +30,14 @@ public class Claws extends SubsystemBase {
|
|||||||
private double m_rightOffset;
|
private double m_rightOffset;
|
||||||
|
|
||||||
private boolean m_open;
|
private boolean m_open;
|
||||||
|
private boolean clawsOpen;
|
||||||
public static enum ClawType {LEFT, RIGHT}
|
public static enum ClawType {LEFT, RIGHT}
|
||||||
|
|
||||||
public Claws(Servo leftClaw, Servo rightClaw) {
|
public Claws(Servo leftClaw, Servo rightClaw) {
|
||||||
m_leftClaw = leftClaw;
|
m_leftClaw = leftClaw;
|
||||||
m_rightClaw = rightClaw;
|
m_rightClaw = rightClaw;
|
||||||
m_open = false;
|
m_open = false;
|
||||||
|
clawsOpen = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -46,11 +48,11 @@ public class Claws extends SubsystemBase {
|
|||||||
if(open) {
|
if(open) {
|
||||||
m_leftClaw.setRaw(ClawConstants.BOTTOM_LIMIT - 900);
|
m_leftClaw.setRaw(ClawConstants.BOTTOM_LIMIT - 900);
|
||||||
m_rightClaw.setRaw(ClawConstants.TOP_LIMIT + 100);
|
m_rightClaw.setRaw(ClawConstants.TOP_LIMIT + 100);
|
||||||
SmartDashboard.putBoolean("Claws Closed", false);
|
clawsOpen = false;
|
||||||
} else {
|
} else {
|
||||||
m_leftClaw.setRaw(ClawConstants.TOP_LIMIT - 400);
|
m_leftClaw.setRaw(ClawConstants.TOP_LIMIT - 400);
|
||||||
m_rightClaw.setRaw(ClawConstants.BOTTOM_LIMIT - 400);
|
m_rightClaw.setRaw(ClawConstants.BOTTOM_LIMIT - 400);
|
||||||
SmartDashboard.putBoolean("Claws Closed", true);
|
clawsOpen = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -62,5 +64,6 @@ public class Claws extends SubsystemBase {
|
|||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
SmartDashboard.putBoolean("Claws Closed", clawsOpen);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -64,7 +64,7 @@ public class Hood extends SubsystemBase {
|
|||||||
// SmartDashboard.putNumber("Hood Angle", m_angleEncoder.getPosition());
|
// SmartDashboard.putNumber("Hood Angle", m_angleEncoder.getPosition());
|
||||||
|
|
||||||
// * speed limiting near soft limits. tolerance (distance when ramping starts) is 20 rotations. speed at hard limits is 0.2 (percent output).
|
// * speed limiting near soft limits. tolerance (distance when ramping starts) is 20 rotations. speed at hard limits is 0.2 (percent output).
|
||||||
runVelocityRamping();
|
// runVelocityRamping();
|
||||||
}
|
}
|
||||||
|
|
||||||
public void runVelocityRamping() {
|
public void runVelocityRamping() {
|
||||||
|
|||||||
Reference in New Issue
Block a user