Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create Drivetrain Simulation #124

Open
wants to merge 7 commits into
base: sim/main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
# Excelsior

Excelsior is the name of our 2022 FRC Robot!

Drivetrain Simulation
6 changes: 2 additions & 4 deletions src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,7 @@

import com.stuypulse.stuylib.input.Gamepad;
import com.stuypulse.stuylib.input.gamepads.*;
import com.stuypulse.stuylib.network.SmartNumber;
import com.stuypulse.robot.commands.BetterShootAnywhere;
import com.stuypulse.robot.commands.ShootAnywhere;
import com.stuypulse.robot.commands.TestAlign;
import com.stuypulse.robot.commands.auton.*;
import com.stuypulse.robot.commands.climber.*;
import com.stuypulse.robot.commands.conveyor.*;
Expand All @@ -20,6 +17,7 @@
import com.stuypulse.robot.commands.shooter.*;
import com.stuypulse.robot.constants.*;
import com.stuypulse.robot.subsystems.*;
import com.stuypulse.robot.subsystems.drivetrain.Drivetrain;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
Expand All @@ -34,7 +32,7 @@ public class RobotContainer {
public final Climber climber = new Climber();
public final ColorSensor colorSensor = new ColorSensor();
public final Conveyor conveyor = new Conveyor(colorSensor);
public final Drivetrain drivetrain = new Drivetrain();
public final IDrivetrain drivetrain = new Drivetrain();
public final Intake intake = new Intake(conveyor);
public final LEDController leds = new LEDController(this);
public final Pump pump = new Pump();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,9 @@
import com.stuypulse.robot.constants.Settings.Limelight;
import com.stuypulse.robot.subsystems.Camera;
import com.stuypulse.robot.subsystems.Conveyor;
import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.Shooter;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

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

Expand All @@ -27,7 +28,7 @@ public class BetterShootAnywhere extends CommandBase {
// subsystems
private final Camera camera;
private final Conveyor conveyor;
private final Drivetrain drivetrain;
private final IDrivetrain drivetrain;
private final Shooter shooter;

// angle control
Expand Down Expand Up @@ -84,7 +85,7 @@ public BetterShootAnywhere(RobotContainer robot) {

@Override
public void initialize() {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);
shooter.retractHood();

angleError.initialize();
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/com/stuypulse/robot/commands/ShootAnywhere.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,21 +13,21 @@

import com.stuypulse.robot.RobotContainer;
import com.stuypulse.robot.commands.conveyor.modes.ConveyorMode;
import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Alignment;
import com.stuypulse.robot.constants.Settings.Limelight;
import com.stuypulse.robot.constants.ShotMap;
import com.stuypulse.robot.subsystems.Conveyor;
import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.Shooter;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandBase;

public class ShootAnywhere extends CommandBase {

private final Conveyor conveyor;
private final Drivetrain drivetrain;
private final IDrivetrain drivetrain;
private final Shooter shooter;

private final IFuser angleError;
Expand Down Expand Up @@ -76,7 +76,7 @@ public ShootAnywhere(RobotContainer robot) {

@Override
public void initialize() {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);
shooter.retractHood();
angleError.initialize();
distance.initialize();
Expand Down
7 changes: 2 additions & 5 deletions src/main/java/com/stuypulse/robot/commands/TestAlign.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,15 +13,12 @@
import com.stuypulse.stuylib.streams.filters.IFilter;
import com.stuypulse.stuylib.streams.filters.LowPassFilter;
import com.stuypulse.robot.RobotContainer;
import com.stuypulse.robot.commands.ThenShoot;
import com.stuypulse.robot.commands.conveyor.modes.ConveyorMode;
import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Alignment;
import com.stuypulse.robot.constants.Settings.Limelight;
import com.stuypulse.robot.constants.Settings.Test;
import com.stuypulse.robot.subsystems.Camera;
import com.stuypulse.robot.subsystems.Conveyor;
import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandBase;
Expand Down Expand Up @@ -80,7 +77,7 @@ public TestAlign(RobotContainer robot) {

@Override
public void initialize() {
robot.drivetrain.setLowGear();
robot.drivetrain.setGear(Gear.LOW);

speedAdjFilter = new LowPassFilter(Alignment.SPEED_ADJ_FILTER);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,15 @@
import com.stuypulse.robot.constants.Settings.Limelight;
import com.stuypulse.robot.subsystems.Camera;
import com.stuypulse.robot.subsystems.Conveyor;
import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

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

public class DrivetrainAlign extends CommandBase {

private final Drivetrain drivetrain;
private final IDrivetrain drivetrain;

private final BStream finished;

Expand All @@ -39,7 +40,7 @@ public class DrivetrainAlign extends CommandBase {
protected final Controller angleController;
protected final Controller distanceController;

public DrivetrainAlign(Drivetrain drivetrain, Camera camera) {
public DrivetrainAlign(IDrivetrain drivetrain, Camera camera) {
this.drivetrain = drivetrain;

// find errors
Expand Down Expand Up @@ -79,7 +80,7 @@ public DrivetrainAlign(Drivetrain drivetrain, Camera camera) {

@Override
public void initialize() {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);

speedAdjFilter = new LowPassFilter(Alignment.SPEED_ADJ_FILTER);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,20 @@

import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Drivetrain.Stalling;
import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

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

public class DrivetrainDrive extends CommandBase {

private final Drivetrain drivetrain;
private final IDrivetrain drivetrain;
private final Gamepad driver;

private final BStream stalling;
private final IStream speed, angle;

public DrivetrainDrive(Drivetrain drivetrain, Gamepad driver) {
public DrivetrainDrive(IDrivetrain drivetrain, Gamepad driver) {
this.drivetrain = drivetrain;
this.driver = driver;

Expand Down Expand Up @@ -54,14 +55,14 @@ public DrivetrainDrive(Drivetrain drivetrain, Gamepad driver) {

public void execute() {
if (driver.getRawLeftButton()) {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);
drivetrain.arcadeDrive(speed.get() - 0.1, angle.get());
} else if (driver.getRawRightButton() || stalling.get()) {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);
drivetrain.arcadeDrive(speed.get(), angle.get());
} else {
drivetrain.setHighGear();
drivetrain.curvatureDrive(speed.get(), angle.get());
drivetrain.setGear(Gear.HIGH);
drivetrain.arcadeDrive(speed.get(), angle.get());
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

package com.stuypulse.robot.commands.drivetrain;

import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.util.TrajectoryLoader;

/**
Expand All @@ -17,7 +17,7 @@
*/
public class DrivetrainDriveDistance extends DrivetrainRamsete {

public DrivetrainDriveDistance(Drivetrain drivetrain, double distance) {
public DrivetrainDriveDistance(IDrivetrain drivetrain, double distance) {
super(drivetrain, TrajectoryLoader.getLine(distance));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,15 @@

package com.stuypulse.robot.commands.drivetrain;

import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;

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

public class DrivetrainDriveForever extends CommandBase {
private final Drivetrain drivetrain;
private final IDrivetrain drivetrain;
private final double speed;

public DrivetrainDriveForever(Drivetrain drivetrain, double speed) {
public DrivetrainDriveForever(IDrivetrain drivetrain, double speed) {
this.drivetrain = drivetrain;
this.speed = speed;

Expand All @@ -24,4 +24,5 @@ public DrivetrainDriveForever(Drivetrain drivetrain, double speed) {
public void execute() {
drivetrain.curvatureDrive(speed, 0);
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -5,21 +5,22 @@

package com.stuypulse.robot.commands.drivetrain;

import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

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

public class DrivetrainHighGear extends InstantCommand {
private Drivetrain drivetrain;
private IDrivetrain drivetrain;

public DrivetrainHighGear(Drivetrain drivetrain) {
public DrivetrainHighGear(IDrivetrain drivetrain) {
this.drivetrain = drivetrain;

addRequirements(this.drivetrain);
}

@Override
public void initialize() {
drivetrain.setHighGear();
drivetrain.setGear(Gear.HIGH);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,21 +5,22 @@

package com.stuypulse.robot.commands.drivetrain;

import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

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

public class DrivetrainLowGear extends InstantCommand {

private Drivetrain drivetrain;
private IDrivetrain drivetrain;

public DrivetrainLowGear(Drivetrain drivetrain) {
public DrivetrainLowGear(IDrivetrain drivetrain) {
this.drivetrain = drivetrain;
addRequirements(drivetrain);
}

@Override
public void initialize() {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -17,21 +17,22 @@
import com.stuypulse.robot.constants.Settings.Limelight;
import com.stuypulse.robot.subsystems.Camera;
import com.stuypulse.robot.subsystems.Conveyor;
import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

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

public class DrivetrainPadAlign extends CommandBase {

private final Drivetrain drivetrain;
private final IDrivetrain drivetrain;

private final BStream finished;

private final IFuser angleError;
protected final Controller angleController;

public DrivetrainPadAlign(Drivetrain drivetrain, Camera camera) {
public DrivetrainPadAlign(IDrivetrain drivetrain, Camera camera) {
this.drivetrain = drivetrain;

// find errors
Expand All @@ -58,7 +59,7 @@ public DrivetrainPadAlign(Drivetrain drivetrain, Camera camera) {

@Override
public void initialize() {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);

angleError.initialize();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,15 @@
import com.stuypulse.robot.constants.Settings.Limelight;
import com.stuypulse.robot.subsystems.Camera;
import com.stuypulse.robot.subsystems.Conveyor;
import com.stuypulse.robot.subsystems.Drivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain;
import com.stuypulse.robot.subsystems.IDrivetrain.Gear;

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

public class DrivetrainPadAlignV2 extends CommandBase {

private final Drivetrain drivetrain;
private final IDrivetrain drivetrain;

private final BStream finished;

Expand All @@ -39,7 +40,7 @@ public class DrivetrainPadAlignV2 extends CommandBase {
protected final Controller angleController;
protected final Controller distanceController;

public DrivetrainPadAlignV2(Drivetrain drivetrain, Camera camera) {
public DrivetrainPadAlignV2(IDrivetrain drivetrain, Camera camera) {
this.drivetrain = drivetrain;

// find errors
Expand Down Expand Up @@ -79,7 +80,7 @@ public DrivetrainPadAlignV2(Drivetrain drivetrain, Camera camera) {

@Override
public void initialize() {
drivetrain.setLowGear();
drivetrain.setGear(Gear.LOW);

speedAdjFilter = new LowPassFilter(Alignment.SPEED_ADJ_FILTER);

Expand Down
Loading