Skip to content

Commit

Permalink
Merge branch 'truher-main'
Browse files Browse the repository at this point in the history
  • Loading branch information
truher committed Jul 18, 2024
2 parents bdcd677 + d6166b9 commit 3a8ceb7
Show file tree
Hide file tree
Showing 98 changed files with 2,670 additions and 1,616 deletions.
44 changes: 44 additions & 0 deletions comp/swerve100/src/main/deploy/practice-field.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
{
"tags": [
{
"ID": 101,
"pose": {
"translation": {
"x": 0.0,
"y": 2.0,
"z": 1.0
},
"rotation": {
"quaternion": {
"W": 1.0,
"X": 0.0,
"Y": 0.0,
"Z": 0.0
}
}
}
},
{
"ID": 102,
"pose": {
"translation": {
"x": 8.0,
"y": 2.0,
"z": 1.0
},
"rotation": {
"quaternion": {
"W": 0.0,
"X": 0.0,
"Y": 0.0,
"Z": 1.0
}
}
}
}
],
"field": {
"length": 8.0,
"width": 4.0
}
}
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
package org.team100.frc2024;

/**
* Always returns false
*/
public class MockSensors implements SensorInterface {

@Override
Expand Down
185 changes: 96 additions & 89 deletions comp/swerve100/src/main/java/org/team100/frc2024/RobotContainer.java

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -111,8 +111,7 @@ public class RobotContainerParkingLot implements Glassy {
driveLogger,
m_heading,
poseEstimator,
swerveLocal,
driverControl::speed);
swerveLocal);

// joel 2/22/24 removing for SVR, put back after that.
// these should be fields
Expand Down Expand Up @@ -256,7 +255,7 @@ public class RobotContainerParkingLot implements Glassy {

// this should be a field.
final DrawSquare m_drawCircle = new DrawSquare(driveLogger, m_drive, controller, viz);
whileTrue(driverControl::circle, m_drawCircle);
whileTrue(driverControl::never, m_drawCircle);
}

private void whileTrue(BooleanSupplier condition, Command command) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,13 @@
import java.util.function.BooleanSupplier;

import org.team100.frc2024.selftest.AmpSelfTest;
import org.team100.lib.commands.drivetrain.DriveManually;
import org.team100.lib.commands.drivetrain.Oscillate;
import org.team100.lib.commands.drivetrain.Veering;
import org.team100.lib.commands.drivetrain.manual.DriveManually;
import org.team100.lib.commands.drivetrain.manual.SimpleManualModuleStates;
import org.team100.lib.dashboard.Glassy;
import org.team100.lib.motion.drivetrain.SwerveDriveSubsystem;
import org.team100.lib.motion.drivetrain.kinodynamics.SwerveKinodynamicsFactory;
import org.team100.lib.motion.drivetrain.manual.SimpleManualModuleStates;
import org.team100.lib.selftest.DefenseSelfTest;
import org.team100.lib.selftest.DriveManuallySelfTest;
import org.team100.lib.selftest.OscillateSelfTest;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,130 @@
package org.team100.frc2024.commands.climber;

import java.util.OptionalDouble;

import org.team100.frc2024.motion.climber.ClimberSubsystem;
import org.team100.lib.dashboard.Glassy;
import org.team100.lib.motion.LimitedLinearMechanism;
import org.team100.lib.telemetry.SupplierLogger;
import org.team100.lib.telemetry.Telemetry.Level;
import org.team100.lib.util.Timer100;
import org.team100.lib.util.Util;

import edu.wpi.first.wpilibj2.command.Command;

/**
* The zeroing process has four states, which are indicated by the states of the
* two timers:
*
* <pre>
* initial: set the effort to low and start the start timer
*
* starting state (start timer running, end timer not running): run at the target speed
*
* transition: when the start timer runs out:
*
* running state (start timer > limit, end timer not running): run at the target speed
*
* transition: when the actual speed is below the threshold, start the stop timer
*
* stopping state (start timer > limit, end timer running): run at the target speed
*
* transition: when the stop timer runs out, zero the mechanism
*
* done state (start timer > limit, end timer > limit): set speed to zero
* </pre>
*/
public class HomeClimber extends Command implements Glassy {
/** Target speed is negative, i.e. down. */
private static final double kTargetSpeedM_S = -0.03;
/** Threshold is unsigned. */
private static final double kThresholdSpeedM_S = 0.003;
/** Wait 0.5s to start moving. */
private static final double kStartTimeS = 0.2;
/** Wait 0.5s to stop moving. */
private static final double kHomeTimeS = 0.2;

private final SupplierLogger m_logger;
private final ClimberSubsystem m_climber;
private final Timer100 m_leftStart;
private final Timer100 m_leftDone;
private final Timer100 m_rightStart;
private final Timer100 m_rightDone;

public HomeClimber(
SupplierLogger logger,
ClimberSubsystem climber) {
m_logger = logger.child(this);
m_climber = climber;
m_leftStart = new Timer100();
m_leftDone = new Timer100();
m_rightStart = new Timer100();
m_rightDone = new Timer100();
}

@Override
public void initialize() {
init(m_leftStart, m_leftDone);
init(m_rightStart, m_rightDone);
m_climber.setHomingForce();
}

@Override
public void execute() {
oneSide("left", m_leftStart, m_leftDone, m_climber.getLeft());
oneSide("right", m_rightStart, m_rightDone, m_climber.getRight());
}

private static void init(Timer100 start, Timer100 done) {
done.stop();
done.reset();
start.restart();
}

private void oneSide(
String name,
Timer100 start,
Timer100 done,
LimitedLinearMechanism mech) {
m_logger.logDouble(Level.TRACE, name + " start timer (s)", start::get);
m_logger.logDouble(Level.TRACE, name + " done timer (s)", done::get);
OptionalDouble opt = mech.getVelocityM_S();
if (opt.isEmpty()) {
Util.warn("HomeClimber: can't home, broken velocity sensor!");
mech.stop();
return;
}
if (start.get() < kStartTimeS) {
// starting up, run the mech unconditionally
mech.setVelocityUnlimited(kTargetSpeedM_S, 0, 0);
} else {
if (done.isStopped()) {
// have not noticed speed decline, keep going.
mech.setVelocityUnlimited(kTargetSpeedM_S, 0, 0);
if (Math.abs(opt.getAsDouble()) < kThresholdSpeedM_S) {
// mech seems stopped, start the done timer
done.start();
}
} else {
if (done.get() < kHomeTimeS) {
// speed is below the threshold, wait a bit.
mech.setVelocityUnlimited(kTargetSpeedM_S, 0, 0);
} else {
// speed has been below the threshold for awhile, so we're done
mech.stop();
mech.resetEncoderPosition();
}
}
}
}

@Override
public boolean isFinished() {
return m_leftDone.get() > kHomeTimeS && m_rightDone.get() > kHomeTimeS;
}

@Override
public String getGlassName() {
return "HomeClimber";
}
}
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
package org.team100.frc2024.motion.drivetrain.manual;
package org.team100.frc2024.commands.drivetrain.manual;

import java.util.Optional;

import org.team100.frc2024.motion.drivetrain.ShooterUtil;
import org.team100.lib.commands.drivetrain.FieldRelativeDriver;
import org.team100.lib.commands.drivetrain.manual.FieldRelativeDriver;
import org.team100.lib.controller.State100;
import org.team100.lib.geometry.TargetUtil;
import org.team100.lib.hid.DriverControl;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
package org.team100.frc2024.motion.drivetrain.manual;
package org.team100.frc2024.commands.drivetrain.manual;

import java.util.Optional;
import java.util.function.BooleanSupplier;

import org.team100.frc2024.motion.drivetrain.ShooterUtil;
import org.team100.lib.commands.drivetrain.FieldRelativeDriver;
import org.team100.lib.commands.drivetrain.manual.FieldRelativeDriver;
import org.team100.lib.controller.State100;
import org.team100.lib.experiments.Experiment;
import org.team100.lib.experiments.Experiments;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
import java.util.OptionalDouble;
import java.util.function.Supplier;

import org.team100.frc2024.commands.drivetrain.manual.ManualWithShooterLock;
import org.team100.frc2024.motion.drivetrain.ShooterUtil;
import org.team100.frc2024.motion.drivetrain.manual.ManualWithShooterLock;
import org.team100.frc2024.motion.intake.Intake;
import org.team100.frc2024.motion.shooter.DrumShooter;
import org.team100.lib.commands.Command100;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@ public AmpPivot(SupplierLogger parent) {
m_logger = parent.child(this);
SysParam m_params = SysParam.neoPositionServoSystem(
55,
60,
60);
5,
5);

TrapezoidProfile100 profile = new TrapezoidProfile100(m_params.maxVelM_S(), m_params.maxAccelM_S2(), 0.05);
double period = 0.02;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,27 +1,39 @@
package org.team100.frc2024.motion.amp;

import java.util.Optional;

import org.team100.frc2024.motion.FeedToAmp;
import org.team100.frc2024.motion.FeederSubsystem;
import org.team100.frc2024.motion.intake.Intake;
import org.team100.frc2024.motion.shooter.DrumShooter;
import org.team100.lib.commands.drivetrain.DriveWithProfile2;
import org.team100.lib.controller.HolonomicDriveController100;
import org.team100.lib.geometry.GeometryUtil;
import org.team100.lib.motion.drivetrain.SwerveDriveSubsystem;
import org.team100.lib.motion.drivetrain.kinodynamics.SwerveKinodynamics;
import org.team100.lib.telemetry.SupplierLogger;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;

public class DriveToAmp extends SequentialCommandGroup {
private static final double kAmpUp = 1.8;
private static final double kCloseToAmpYM = 6.799454;
private static final double kNearAmpYM = 6.474794;
private static final double kAmpXM = 1.834296;
private static final double kFieldWidthM = 8.221;

private static final Pose2d kBlueNearAmp = new Pose2d(
kAmpXM, kNearAmpYM, GeometryUtil.kRotation90);
private static final Pose2d kRedNearAmp = new Pose2d(
kAmpXM, kFieldWidthM - kNearAmpYM, GeometryUtil.kRotation90);
private static final Pose2d kBlueCloseToAmp = new Pose2d(
kAmpXM, kCloseToAmpYM, GeometryUtil.kRotation90);
private static final Pose2d kRedCloseToAmp = new Pose2d(
kAmpXM, kFieldWidthM - kCloseToAmpYM, GeometryUtil.kRotation90);

public DriveToAmp(
SupplierLogger parent,
SwerveDriveSubsystem drive,
Expand All @@ -32,38 +44,31 @@ public DriveToAmp(
DrumShooter shooter,
FeederSubsystem feeder) {

Optional<Alliance> optAlliance = DriverStation.getAlliance();
if (optAlliance.isEmpty()) {
return;
}
Alliance alliance = optAlliance.get();
if (alliance == Alliance.Blue) {
addCommands(
new DriveWithProfile2(parent, () -> new Pose2d(1.834296, 6.474794, new Rotation2d(Math.PI / 2)),
drive,
new HolonomicDriveController100(parent), limits),
new ParallelCommandGroup(new AmpSet(parent, amp, 1.8),
new SequentialCommandGroup(
new DriveWithProfile2(parent,
() -> new Pose2d(1.834296, 6.799454, new Rotation2d(Math.PI / 2)), drive,
new HolonomicDriveController100(parent), limits),
new ParallelCommandGroup(ampFeeder.run(ampFeeder::outtake), new WaitCommand(1)))));
} else {
addCommands(
new ParallelDeadlineGroup(
new DriveWithProfile2(parent,
() -> new Pose2d(1.834296, 8.221 - 6.474794, new Rotation2d(Math.PI / 2)),
drive,
new HolonomicDriveController100(parent), limits),
new FeedToAmp(intake, shooter, ampFeeder, feeder)),
new ParallelCommandGroup(new AmpSet(parent, amp, 1.8),
new SequentialCommandGroup(
new DriveWithProfile2(parent,
() -> new Pose2d(1.834296, 8.221 - 6.799454, new Rotation2d(Math.PI / 2)),
drive,
new HolonomicDriveController100(parent), limits),
new ParallelCommandGroup(ampFeeder.run(ampFeeder::outtake), new WaitCommand(1)))));
}
addCommands(
new ParallelDeadlineGroup(
new DriveWithProfile2(parent,
() -> DriverStation.getAlliance().map(
x -> switch (x) {
case Red -> kRedNearAmp;
case Blue -> kBlueNearAmp;
}),
drive,
new HolonomicDriveController100(parent), limits),
new FeedToAmp(intake, shooter, ampFeeder, feeder)),
new ParallelCommandGroup(
new AmpSet(parent, amp, kAmpUp),
new SequentialCommandGroup(
new DriveWithProfile2(parent,
() -> DriverStation.getAlliance().map(
x -> switch (x) {
case Red -> kRedCloseToAmp;
case Blue -> kBlueCloseToAmp;
}),
drive,
new HolonomicDriveController100(parent), limits),
new ParallelCommandGroup(
ampFeeder.run(ampFeeder::outtake),
new WaitCommand(1)))));

}
}
Loading

0 comments on commit 3a8ceb7

Please sign in to comment.