Skip to content

Commit

Permalink
update command logic and abstract auton path
Browse files Browse the repository at this point in the history
  • Loading branch information
QuackingBob committed May 27, 2022
1 parent 7a37576 commit b1581a4
Show file tree
Hide file tree
Showing 6 changed files with 180 additions and 37 deletions.
31 changes: 31 additions & 0 deletions images/stuff.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
// TrajectoryConfig trajectoryConfig = new TrajectoryConfig(
// Constants.SwerveDrivetrain.kDriveMaxSpeedMPS,
// Constants.SwerveDrivetrain.kDriveMaxAcceleration);
// trajectoryConfig.setKinematics(swerveDrivetrain.getKinematics());

// Trajectory trajectory = TrajectoryGenerator.generateTrajectory(
// new Pose2d(0, 0, new Rotation2d(0)),
// List.of(
// new Translation2d(1, 2),
// new Translation2d(3, 1)
// ),
// new Pose2d(4, 2, Rotation2d.fromDegrees(180.0)),
// trajectoryConfig);

// swerveDrivetrain.getField().getObject("traj").setTrajectory(trajectory);

// SwerveControllerCommand swerveControllerCommand = new SwerveControllerCommand(
// trajectory,
// swerveDrivetrain::getSimPose,
// swerveDrivetrain.getKinematics(),
// swerveDrivetrain.xController,
// swerveDrivetrain.yController,
// swerveDrivetrain.thetaController,
// swerveDrivetrain::setModuleStates,
// swerveDrivetrain);

// return new SequentialCommandGroup(
// new InstantCommand(() -> swerveDrivetrain.resetSimOdometry(trajectory.getInitialPose())),
// swerveControllerCommand,
// new InstantCommand(() -> swerveDrivetrain.stopModules())
// );
9 changes: 9 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
"/LiveWindow/Ungrouped/PIDController[7]": "PIDController",
"/LiveWindow/Ungrouped/Scheduler": "Scheduler",
"/LiveWindow/Ungrouped/navX-Sensor[4]": "Gyro",
"/SmartDashboard/Auton Selector": "String Chooser",
"/SmartDashboard/Field": "Field2d"
},
"windows": {
Expand All @@ -39,6 +40,11 @@
"visible": true
}
},
"/SmartDashboard/Auton Selector": {
"window": {
"visible": true
}
},
"/SmartDashboard/Field": {
"Robot": {
"style": "Box/Image"
Expand All @@ -58,6 +64,9 @@
"open": true
},
"SmartDashboard": {
"Auton Selector": {
"open": true
},
"Field": {
"open": true
},
Expand Down
40 changes: 8 additions & 32 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.commands.AutonPathExample;
import frc.robot.commands.SwerveJoystickCommand;
import frc.robot.subsystems.SwerveDrivetrain;
import edu.wpi.first.wpilibj2.command.Command;
Expand All @@ -36,14 +39,15 @@ public class RobotContainer {

private final Joystick driveJoystick = new Joystick(Constants.SwerveDrivetrain.kDriveJoystickPort);

private final SendableChooser<Command> autonSelector = new SendableChooser<>();
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
swerveDrivetrain.setDefaultCommand(new SwerveJoystickCommand(
swerveDrivetrain,
() -> -driveJoystick.getRawAxis(Constants.SwerveDrivetrain.kDriveXAxis),
() -> -driveJoystick.getRawAxis(Constants.SwerveDrivetrain.kDriveYAxis),
() -> -driveJoystick.getRawAxis(Constants.SwerveDrivetrain.kDriveWAxis),
() -> !driveJoystick.getRawButton(Constants.SwerveDrivetrain.kDriveFieldOrientButtonIdx)));
() -> driveJoystick.getRawButton(Constants.SwerveDrivetrain.kDriveFieldOrientButtonIdx)));

// Configure the button bindings
configureButtonBindings();
Expand All @@ -70,6 +74,8 @@ private void configureButtonBindings() {
.whenPressed(() -> swerveDrivetrain.setRotationPointIdx(4))
.whenReleased(() -> swerveDrivetrain.setRotationPointIdx(0));

autonSelector.setDefaultOption("Example", new AutonPathExample(swerveDrivetrain));
SmartDashboard.putData("Auton Selector", autonSelector);
}

/**
Expand All @@ -78,36 +84,6 @@ private void configureButtonBindings() {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
TrajectoryConfig trajectoryConfig = new TrajectoryConfig(
Constants.SwerveDrivetrain.kDriveMaxSpeedMPS,
Constants.SwerveDrivetrain.kDriveMaxAcceleration);
trajectoryConfig.setKinematics(swerveDrivetrain.getKinematics());

Trajectory trajectory = TrajectoryGenerator.generateTrajectory(
new Pose2d(0, 0, new Rotation2d(0)),
List.of(
new Translation2d(1, 2),
new Translation2d(3, 1)
),
new Pose2d(4, 2, Rotation2d.fromDegrees(180.0)),
trajectoryConfig);

swerveDrivetrain.getField().getObject("traj").setTrajectory(trajectory);

SwerveControllerCommand swerveControllerCommand = new SwerveControllerCommand(
trajectory,
swerveDrivetrain::getSimPose,
swerveDrivetrain.getKinematics(),
swerveDrivetrain.xController,
swerveDrivetrain.yController,
swerveDrivetrain.thetaController,
swerveDrivetrain::setModuleStates,
swerveDrivetrain);

return new SequentialCommandGroup(
new InstantCommand(() -> swerveDrivetrain.resetSimOdometry(trajectory.getInitialPose())),
swerveControllerCommand,
new InstantCommand(() -> swerveDrivetrain.stopModules())
);
return autonSelector.getSelected();
}
}
83 changes: 83 additions & 0 deletions src/main/java/frc/robot/commands/AutonPathExample.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
// 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 java.util.List;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.SwerveControllerCommand;
import frc.robot.subsystems.SwerveDrivetrain;

public class AutonPathExample extends SequentialCommandGroup {
/** Creates a new AutonPathExample. */
private final SwerveDrivetrain swerveDrivetrain;
private SwerveControllerCommand swerveControllerCommand;
private Trajectory trajectory;

public AutonPathExample(SwerveDrivetrain drivetrain) {
// Use addRequirements() here to declare subsystem dependencies.
this.swerveDrivetrain = drivetrain;
addRequirements(drivetrain);

trajectory = TrajectoryGenerator.generateTrajectory(
new Pose2d(0, 0, new Rotation2d(0)),
List.of(
new Translation2d(1, 2),
new Translation2d(3, 1)
),
new Pose2d(4, 2, Rotation2d.fromDegrees(180.0)),
swerveDrivetrain.getTrajectoryConfig());

swerveDrivetrain.getField().getObject("traj").setTrajectory(trajectory);

swerveControllerCommand = new SwerveControllerCommand(
trajectory,
swerveDrivetrain::getSimPose,
swerveDrivetrain.getKinematics(),
swerveDrivetrain.xController,
swerveDrivetrain.yController,
swerveDrivetrain.thetaController,
swerveDrivetrain::setModuleStates,
swerveDrivetrain);

addCommands(
new InstantCommand(() -> swerveDrivetrain.resetSimOdometry(trajectory.getInitialPose())),
swerveControllerCommand,
new InstantCommand(() -> swerveDrivetrain.stopModules()));
}

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

@Override
public void execute() {
super.execute();
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
super.end(interrupted);
swerveDrivetrain.setDisabled();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return super.isFinished();
}
}
7 changes: 5 additions & 2 deletions src/main/java/frc/robot/commands/SwerveJoystickCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,9 @@ public SwerveJoystickCommand(SwerveDrivetrain drivetrain, Supplier<Double> xSpee

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

// Called every time the scheduler runs while the command is scheduled.
@Override
Expand All @@ -60,7 +62,7 @@ public void execute() {
ChassisSpeeds chassisSpeeds;
if (fieldOrientedFunc.get()) {
chassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(
vX, vY, vW, drivetrain.getRotation2d());
vY, vX, vW, drivetrain.getSimRotation2d());
}
else {
chassisSpeeds = new ChassisSpeeds(vX, vY, vW);
Expand All @@ -80,6 +82,7 @@ public void execute() {
@Override
public void end(boolean interrupted) {
drivetrain.stopModules();
drivetrain.setDisabled();
}

// Returns true when the command should end.
Expand Down
47 changes: 44 additions & 3 deletions src/main/java/frc/robot/subsystems/SwerveDrivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,26 +8,32 @@

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.wpilibj.SPI;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.SwerveControllerCommand;
import frc.robot.Constants;
import frc.robot.subsystems.SwerveModule;

public class SwerveDrivetrain extends SubsystemBase {
// state stuff
public static enum DrivetrainState {
AUTON_PATH, JOYSTICK_DRIVE
AUTON_PATH, JOYSTICK_DRIVE, DISABLED
}

private DrivetrainState state;
Expand All @@ -43,10 +49,10 @@ public static enum DrivetrainState {
private SwerveDriveOdometry simOdometry;
private SwerveDriveOdometry odometry;
private Field2d field;
private SimpleMotorFeedforward feedforward;
public PIDController xController;
public PIDController yController;
public ProfiledPIDController thetaController;
private TrajectoryConfig trajectoryConfig;

// sensors
private AHRS gyro;
Expand Down Expand Up @@ -136,6 +142,12 @@ public SwerveDrivetrain() {
Constants.SwerveDrivetrain.m_r_control_D,
Constants.SwerveDrivetrain.kThetaControllerConstraints);
thetaController.enableContinuousInput(-Math.PI, Math.PI);

trajectoryConfig = new TrajectoryConfig(
Constants.SwerveDrivetrain.kDriveMaxSpeedMPS,
Constants.SwerveDrivetrain.kDriveMaxAcceleration);
trajectoryConfig.setKinematics(swerveKinematics);
state = DrivetrainState.JOYSTICK_DRIVE;
}

public void zeroHeading() {
Expand All @@ -156,6 +168,10 @@ public Rotation2d getRotation2d() {
return Rotation2d.fromDegrees(getHeading());
}

public Rotation2d getSimRotation2d() {
return new Rotation2d(simulationData.getHeading());
}

@Override
public void periodic() {
// This method will be called once per scheduler run
Expand Down Expand Up @@ -278,4 +294,29 @@ public int getRotationPointIdx() {
public void setRotationPointIdx(int idx) {
rotationPoint = idx;
}

public TrajectoryConfig getTrajectoryConfig() {
return trajectoryConfig;
}

public SequentialCommandGroup getDriveSimCommand(SwerveControllerCommand swerveCommand, Trajectory trajectory) {
Command swerveControllerCommand;
return new SequentialCommandGroup(
new InstantCommand(() -> resetSimOdometry(trajectory.getInitialPose())),
swerveCommand,
new InstantCommand(() -> stopModules())
);
}

public void setAutonomous() {
state = DrivetrainState.AUTON_PATH;
}

public void setJoystick() {
state = DrivetrainState.JOYSTICK_DRIVE;
}

public void setDisabled() {
state = DrivetrainState.DISABLED;
}
}

0 comments on commit b1581a4

Please sign in to comment.