Skip to content

Commit

Permalink
Create Demo Commands (#5)
Browse files Browse the repository at this point in the history
* Create Demo Commands

* Fix Translate.java & Add JavaDocs

* Bontia Sim
  • Loading branch information
ACat701 authored Aug 31, 2024
1 parent 7f775e9 commit 83f2290
Show file tree
Hide file tree
Showing 10 changed files with 354 additions and 42 deletions.
10 changes: 10 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
@@ -1,4 +1,11 @@
{
"HALProvider": {
"Other Devices": {
"window": {
"visible": false
}
}
},
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo",
Expand All @@ -22,6 +29,9 @@
}
}
},
"NetworkTables Info": {
"visible": true
},
"Plot": {
"Plot <0>": {
"window": {
Expand Down
47 changes: 30 additions & 17 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,13 @@
import com.ctre.phoenix6.signals.SensorDirectionValue;
import com.frcteam3255.components.swerve.SN_SwerveConstants;

import edu.wpi.first.math.util.Units;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.Angle;
import edu.wpi.first.units.Distance;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Units;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;

Expand All @@ -30,10 +36,10 @@ public static class constDrivetrain {
// In Rotations: Obtain by aligning all of the wheels in the correct direction
// and
// copy-pasting the Raw Absolute Encoder value
public static final double FRONT_LEFT_ABS_ENCODER_OFFSET = 0.322754;
public static final double FRONT_RIGHT_ABS_ENCODER_OFFSET = -0.045410;
public static final double BACK_LEFT_ABS_ENCODER_OFFSET = -0.192871;
public static final double BACK_RIGHT_ABS_ENCODER_OFFSET = -0.314941;
public static final double FRONT_LEFT_ABS_ENCODER_OFFSET = 0.417236;
public static final double FRONT_RIGHT_ABS_ENCODER_OFFSET = -0.254395;
public static final double BACK_LEFT_ABS_ENCODER_OFFSET = 0.258789;
public static final double BACK_RIGHT_ABS_ENCODER_OFFSET = -0.290039;

public static final InvertedValue DRIVE_MOTOR_INVERT = InvertedValue.CounterClockwise_Positive;
public static final InvertedValue STEER_MOTOR_INVERT = InvertedValue.Clockwise_Positive;
Expand All @@ -42,7 +48,7 @@ public static class constDrivetrain {
public static final NeutralModeValue DRIVE_NEUTRAL_MODE = NeutralModeValue.Brake;
public static final NeutralModeValue STEER_NEUTRAL_MODE = NeutralModeValue.Coast;

public static final double WHEEL_DIAMETER = Units.inchesToMeters(3.8);
public static final double WHEEL_DIAMETER = 0.09779;
public static final double WHEEL_CIRCUMFERENCE = WHEEL_DIAMETER * Math.PI;

// Taken from the online listing
Expand All @@ -56,31 +62,36 @@ public static class constDrivetrain {
* </p>
* <b>Units:</b> Meters Per Second
*/
public static final double THEORETICAL_MAX_DRIVE_SPEED = SN_SwerveConstants.MK4I.KRAKEN.L3.maxSpeedMeters;
public static final double THEORETICAL_MAX_DRIVE_SPEED = SN_SwerveConstants.MK4I.FALCON.L3.maxSpeedMeters;

/**
/**
* <p>
* Observed maximum translational speed while manually driving on the
* Competition Robot.
* </p>
* <b>Units:</b> Meters Per Second
*/
public static final double DRIVE_SPEED = Units.feetToMeters(15.1);
public static final Measure<Velocity<Distance>> DRIVE_SPEED = Units.FeetPerSecond.of(15.1);
// Physically measured from center to center of the wheels
public static final double TRACK_WIDTH = Units.inchesToMeters(23.75); // Distance between Left & Right Wheels
public static final double WHEELBASE = Units.inchesToMeters(23.75); // Distance between Front & Back Wheels
// Distance between Left & Right Wheels
public static final double TRACK_WIDTH = Units.Meters.convertFrom(23.75, Units.Inches);
// Distance between Front & Back Wheels
public static final double WHEELBASE = Units.Meters.convertFrom(23.75, Units.Inches);

public static final SN_SwerveConstants SWERVE_CONSTANTS = new SN_SwerveConstants(
SN_SwerveConstants.MK4I.KRAKEN.L3.steerGearRatio,
SN_SwerveConstants.MK4I.FALCON.L3.steerGearRatio,
0.09779 * Math.PI,
SN_SwerveConstants.MK4I.KRAKEN.L3.driveGearRatio,
SN_SwerveConstants.MK4I.KRAKEN.L3.maxSpeedMeters);
SN_SwerveConstants.MK4I.FALCON.L3.driveGearRatio,
SN_SwerveConstants.MK4I.FALCON.L3.maxSpeedMeters);

public static final double AT_ROTATION_TOLERANCE = 0.1;
public static final Measure<Distance> AT_POINT_TOLERANCE = Units.Meters.of(0.1);

}

public static class constField {
public static Optional<Alliance> ALLIANCE = Optional.empty();
/**

/**
* Boolean that controls when the path will be mirrored for the red
* alliance. This will flip the path being followed to the red side of the
* field.
Expand All @@ -96,5 +107,7 @@ public static boolean isRedAlliance() {
}
return false;
};

public static final Pose2d WORKSHOP_STARTING_POSE = new Pose2d(0, 0, new Rotation2d(0));
}
}
15 changes: 11 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,15 @@
package frc.robot;

import com.frcteam3255.joystick.SN_XboxController;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.Constants.constControllers;
import frc.robot.RobotMap.mapControllers;
import frc.robot.commands.Drive;
import frc.robot.commands.DriveManual;
import frc.robot.commands.ExampleAuto;
import frc.robot.subsystems.Drivetrain;

public class RobotContainer {
Expand All @@ -22,7 +26,8 @@ public RobotContainer() {
conDriver.setLeftDeadband(constControllers.DRIVER_LEFT_STICK_DEADBAND);

subDrivetrain
.setDefaultCommand(new Drive(subDrivetrain, conDriver.axis_LeftY, conDriver.axis_LeftX, conDriver.axis_RightX));
.setDefaultCommand(
new DriveManual(subDrivetrain, conDriver.axis_LeftY, conDriver.axis_LeftX, conDriver.axis_RightX));

configureBindings();

Expand All @@ -31,7 +36,8 @@ public RobotContainer() {

private void configureBindings() {
conDriver.btn_B.onTrue(Commands.runOnce(() -> subDrivetrain.resetModulesToAbsolute()));
conDriver.btn_Back.onTrue(Commands.runOnce(() -> subDrivetrain.resetYaw()));
conDriver.btn_Back
.onTrue(Commands.runOnce(() -> subDrivetrain.resetPoseToPose(new Pose2d(0, 0, new Rotation2d()))));

// Defaults to Field-Relative, is Robot-Relative while held
conDriver.btn_LeftBumper
Expand All @@ -40,6 +46,7 @@ private void configureBindings() {
}

public Command getAutonomousCommand() {
return null;
return Commands.runOnce(() -> subDrivetrain.resetPoseToPose(Constants.constField.WORKSHOP_STARTING_POSE))
.andThen(new ExampleAuto(subDrivetrain));
}
}
26 changes: 16 additions & 10 deletions src/main/java/frc/robot/RobotPreferences.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,16 @@

import com.frcteam3255.preferences.SN_DoublePreference;

import edu.wpi.first.math.util.Units;
import edu.wpi.first.units.Units;

public class RobotPreferences {
public static final class prefDrivetrain {
public static final SN_DoublePreference minimumSteerSpeedPercent = new SN_DoublePreference(
"minimumSteerSpeed", 0.01);

// Translational speed (feet per second) while manually driving
public static final SN_DoublePreference driveSpeed = new SN_DoublePreference("driveSpeed", Constants.constDrivetrain.DRIVE_SPEED);
public static final SN_DoublePreference driveSpeed = new SN_DoublePreference("driveSpeed",
Constants.constDrivetrain.DRIVE_SPEED.in(Units.MetersPerSecond));

// Rotational speed (degrees per second) while manually driving
public static final SN_DoublePreference turnSpeed = new SN_DoublePreference("turnSpeed", 360);
Expand All @@ -36,30 +37,35 @@ public static final class prefDrivetrain {
* <b>Units:</b> Radians
*/
public static final SN_DoublePreference measurementStdDevsHeading = new SN_DoublePreference(
"measurementStdDevsHeading", Units.degreesToRadians(5));
"measurementStdDevsHeading", Units.Radians.convertFrom(5, Units.Degrees));

// This PID is implemented on each module, not the Drivetrain subsystem.
public static final SN_DoublePreference driveP = new SN_DoublePreference("driveP", 0);
public static final SN_DoublePreference driveP = new SN_DoublePreference("driveP", 0.18);
public static final SN_DoublePreference driveI = new SN_DoublePreference("driveI", 0.0);
public static final SN_DoublePreference driveD = new SN_DoublePreference("driveD", 1);

public static final SN_DoublePreference driveD = new SN_DoublePreference("driveD", 0);

public static final SN_DoublePreference steerP = new SN_DoublePreference("steerP", 1);
public static final SN_DoublePreference steerP = new SN_DoublePreference("steerP", 100);
public static final SN_DoublePreference steerI = new SN_DoublePreference("steerI", 0.0);
public static final SN_DoublePreference steerD = new SN_DoublePreference("steerD", 0.0);
public static final SN_DoublePreference steerD = new SN_DoublePreference("steerD", 0.14414076246334312);

public static final SN_DoublePreference driveKs = new SN_DoublePreference("driveKs", 0);
public static final SN_DoublePreference driveKa = new SN_DoublePreference("driveKa", 0);
public static final SN_DoublePreference driveKv = new SN_DoublePreference("driveKv", (1 / driveSpeed.getValue()));

// This PID is implemented on the Drivetrain subsystem
public static final SN_DoublePreference autoDriveP = new SN_DoublePreference("autoDriveP", 2);
public static final SN_DoublePreference autoDriveP = new SN_DoublePreference("autoDriveP", 8);
public static final SN_DoublePreference autoDriveI = new SN_DoublePreference("autoDriveI", 0);
public static final SN_DoublePreference autoDriveD = new SN_DoublePreference("autoDriveD", 0);

public static final SN_DoublePreference autoSteerP = new SN_DoublePreference("autoSteerP", 0.5);
public static final SN_DoublePreference autoSteerP = new SN_DoublePreference("autoSteerP", 2.5);
public static final SN_DoublePreference autoSteerI = new SN_DoublePreference("autoSteerI", 0.0);
public static final SN_DoublePreference autoSteerD = new SN_DoublePreference("autoSteerD", 0.0);

// Teleop Snapping to Rotation (Yaw)
public static final SN_DoublePreference yawSnapP = new SN_DoublePreference("yawSnapP", 3);
public static final SN_DoublePreference yawSnapI = new SN_DoublePreference("yawSnapI", 0);
public static final SN_DoublePreference yawSnapD = new SN_DoublePreference("yawSnapD", 0);

}

public static final class prefVision {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
import frc.robot.RobotPreferences.prefDrivetrain;
import frc.robot.subsystems.Drivetrain;

public class Drive extends Command {
public class DriveManual extends Command {
Drivetrain subDrivetrain;
DoubleSupplier xAxis, yAxis, rotationAxis;
boolean isOpenLoop;

public Drive(Drivetrain subDrivetrain, DoubleSupplier xAxis, DoubleSupplier yAxis,
public DriveManual(Drivetrain subDrivetrain, DoubleSupplier xAxis, DoubleSupplier yAxis,
DoubleSupplier rotationAxis) {
this.subDrivetrain = subDrivetrain;
this.xAxis = xAxis;
Expand Down
50 changes: 50 additions & 0 deletions src/main/java/frc/robot/commands/ExampleAuto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;

import edu.wpi.first.units.Units;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.subsystems.Drivetrain;

public class ExampleAuto extends SequentialCommandGroup {
Drivetrain subDrivetrain;

/** Creates a new ExampleAuto. */
public ExampleAuto(Drivetrain subDrivetrain) {
/*
* @formatter:off
*
* Self-Driving Robot Workshop Usage:
* 1. Build your self-driving robot command using the following commands:
* a. RotateInPlace
* b. Translate
* c. Commands.waitSeconds
* An example is already done for you below, but feel free to remove it and get creative!
*
* 2. View a simulation of your robot driving!
* a. Press Ctrl+Shift+P or click the WPILib logo in the top right to open the command pallette.
* b. Type or select "WPILib: Simulate Robot Code".
* c. Once the code is done building, select "SIM GUI" from the pop-up window.
* d. Use Field2d or AdvantageScope to view your robot
* e. Run the autonomous by selecting "Autonomous" from Glass
*
* 3. Run your path on the real robot
* a. Place the robot in our specified starting location
* b. Connect to the robot using a DriverStation laptop
* c. Run FRC DriverStation
* d. When you're ready, enable the robot in Autonomous
*
* @formatter:on
*/

addCommands(
new Translate(subDrivetrain, Units.Meters.of(1), Units.Degrees.of(45), Units.Percent.of(1)),
Commands.waitSeconds(0.5),
new RotateInPlace(subDrivetrain, Units.Degrees.of(45)),
Commands.waitSeconds(0.5),
new Translate(subDrivetrain, Units.Meters.of(2), Units.Degrees.of(-45), Units.Percent.of(0.5)));
}
}
69 changes: 69 additions & 0 deletions src/main/java/frc/robot/commands/RotateInPlace.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.units.Angle;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Units;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.constDrivetrain;
import frc.robot.subsystems.Drivetrain;

public class RotateInPlace extends Command {
Drivetrain subDrivetrain;
Measure<Angle> desiredRotation;
Measure<Velocity<Angle>> rVelocity;
final boolean isOpenLoop = false;

/**
* Rotates the robot in place to face a given Field-Relative rotation.
*
* @param subDrivetrain The instance of the subsystem we are making run this
* command
* @param desiredRotation The desired angle you would like to rotate towards
* (Field-Relative Angle)
*
* @see <a href=
* "https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html">Field
* Coordinate System</a>
*
*/
public RotateInPlace(Drivetrain subDrivetrain, Measure<Angle> desiredRotation) {
this.subDrivetrain = subDrivetrain;
this.desiredRotation = desiredRotation;

// Use addRequirements() here to declare subsystem dependencies.
addRequirements(subDrivetrain);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
rVelocity = subDrivetrain.getVelocityToRotate(desiredRotation);

subDrivetrain.drive(new Translation2d(0, 0), rVelocity.in(Units.RadiansPerSecond), isOpenLoop);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
subDrivetrain.drive(new Translation2d(0, 0), 0, isOpenLoop);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return subDrivetrain.getRotationMeasure().isNear(desiredRotation,
constDrivetrain.AT_ROTATION_TOLERANCE);
}
}
Loading

0 comments on commit 83f2290

Please sign in to comment.