Skip to content
Merged
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
25 changes: 1 addition & 24 deletions src/main/java/frc/JoysticksBindings.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,8 @@
package frc;

import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.joysticks.JoystickPorts;
import frc.joysticks.SmartJoystick;
import frc.robot.Robot;
import frc.robot.structures.FollowTrajectoryDemo;


public class JoysticksBindings {
Expand All @@ -29,27 +26,7 @@ public static void configureBindings(Robot robot) {
private static void mainJoystickButtons(Robot robot) {
SmartJoystick usedJoystick = MAIN_JOYSTICK;
// bindings...
// robot.getArm().applyTestBinds(usedJoystick);
usedJoystick.A.onTrue(
new InstantCommand(() -> robot.getArmVisualizer().showPath(Robot.pathDown.getStates())).andThen(new WaitCommand(0.3))
.andThen(new FollowTrajectoryDemo(Robot.pathDown, p -> robot.getArm().setPosition(p, true)))
);
usedJoystick.B.onTrue(
new InstantCommand(() -> robot.getArmVisualizer().showPath(Robot.pathLeft.getStates())).andThen(new WaitCommand(0.3))
.andThen(new FollowTrajectoryDemo(Robot.pathLeft, p -> robot.getArm().setPosition(p, false)))
);
usedJoystick.Y.onTrue(
new InstantCommand(() -> robot.getArmVisualizer().showPath(Robot.pathUp.getStates())).andThen(new WaitCommand(0.3))
.andThen(new FollowTrajectoryDemo(Robot.pathUp, p -> robot.getArm().setPosition(p, false)))
);

// List<Pair<Translation2d, Boolean>> flipArm = PathGenerator
// .flipArm(Robot.pathLeft.get(Robot.pathLeft.size() - 1), false, DoubleJointedArm.TOTAL_LENGTH_METERS);
// usedJoystick.X.onTrue(
// new InstantCommand(() -> robot.getArmVisualizer().showPath(PathGenerator.createTranslation2dList(flipArm)))
// .andThen(new WaitCommand(0.3))
// .andThen(new FollowPathWithSideCommand(flipArm, p -> robot.getArm().setPosition(p.getFirst(), p.getSecond())))
// );
robot.getArm().applyTestBinds(usedJoystick);
}

private static void secondJoystickButtons(Robot robot) {
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public Robot() {

pathLeft = TrajectoryGenerator.generateTrajectory(
new Pose2d(new Translation2d(-0.4, 1), Rotation2d.fromDegrees(0)),
List.of(),
List.of(new Translation2d(0.1, 1.2)),
new Pose2d(new Translation2d(0.4, 1), Rotation2d.fromDegrees(0)),
new TrajectoryConfig(2, 2).setStartVelocity(0).setEndVelocity(0)
);
Expand All @@ -73,6 +73,9 @@ public void periodic() {

armVisualizer.setAngles(arm.getElbowAngle(), arm.getWristAngle());
armVisualizer.setTargetPositionMeters(arm.getPositionMeters());
if (arm.hasTrajectoryChanged()) {
armVisualizer.showPath(arm.getCurrentTrajectory().getStates());
}

CommandScheduler.getInstance().run(); // Should be last
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,15 @@
package frc.robot.structures.doublejointedarm;

import edu.wpi.first.math.MathUtil;
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.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.joysticks.Axis;
import frc.joysticks.SmartJoystick;
import frc.robot.Robot;
import frc.robot.structures.FollowTrajectoryDemo;
import frc.robot.subsystems.GBSubsystem;
import frc.utils.alerts.Alert;
import org.littletonrobotics.junction.Logger;
Expand All @@ -15,14 +21,32 @@ public class DoubleJointedArm extends GBSubsystem {
public static final double ELBOW_LENGTH_METERS = 0.8;
public static final double WRIST_LENGTH_METERS = 0.5;
public static final double TOTAL_LENGTH_METERS = ELBOW_LENGTH_METERS + WRIST_LENGTH_METERS;
public static final Rotation2d SWITCH_DIRECTION_TOLERANCE = Rotation2d.fromDegrees(3);

private Rotation2d elbowAngle = new Rotation2d();
private Rotation2d wristAngle = new Rotation2d();
private Trajectory currentTrajectory = null;
private boolean hasTrajectoryChanged = false;

public DoubleJointedArm(String logPath) {
super(logPath);
}

public boolean hasTrajectoryChanged() {
boolean check = hasTrajectoryChanged;
hasTrajectoryChanged = false;
return check;
}

public Trajectory getCurrentTrajectory() {
return currentTrajectory;
}

public void setCurrentTrajectory(Trajectory currentTrajectory) {
hasTrajectoryChanged = true;
this.currentTrajectory = currentTrajectory;
}

@Override
protected void subsystemPeriodic() {
Logger.recordOutput(getLogPath() + "/ElbowAngleDeg", elbowAngle.getDegrees());
Expand Down Expand Up @@ -64,11 +88,24 @@ public void setPosition(Translation2d positionMeters, boolean isElbowLeft) {
setAngles(targetAngles.get().elbowAngle(), targetAngles.get().wristAngle());
}

private static Optional<ArmAngles> toAngles(Translation2d positionMeters, boolean isElbowLeft) {
public void setPosition(Translation2d positionMeters) {
setPosition(positionMeters, isElbowLeft(positionMeters));
}

private boolean isElbowLeft(Translation2d positionMeters) {
double elbowRads = getElbowAngle().getRadians();
double positionRads = positionMeters.getAngle().getRadians();
double distanceFromStraightLineRads = Math.abs(MathUtil.angleModulus(elbowRads - positionRads));

boolean isLettingAutoPick = distanceFromStraightLineRads < SWITCH_DIRECTION_TOLERANCE.getRadians();
return isLettingAutoPick ? positionMeters.getX() > 0 : elbowRads > positionRads;
}

private Optional<ArmAngles> toAngles(Translation2d positionMeters, boolean isElbowLeft) {
return DoubleJointedArmKinematics.toAngles(positionMeters, ELBOW_LENGTH_METERS, WRIST_LENGTH_METERS, isElbowLeft);
}

private static Translation2d toPositionMeters(Rotation2d elbowAngle, Rotation2d wristAngle) {
private Translation2d toPositionMeters(Rotation2d elbowAngle, Rotation2d wristAngle) {
return DoubleJointedArmKinematics.toPositionMeters(new ArmAngles(elbowAngle, wristAngle), ELBOW_LENGTH_METERS, WRIST_LENGTH_METERS);
}

Expand All @@ -86,6 +123,23 @@ public void applyTestBinds(SmartJoystick joystick) {
.onTrue(new InstantCommand(() -> setPosition(toPositionMeters(Rotation2d.fromDegrees(150), Rotation2d.fromDegrees(75)), true)));
joystick.POV_UP
.onTrue(new InstantCommand(() -> setPosition(toPositionMeters(Rotation2d.fromDegrees(75), Rotation2d.fromDegrees(120)), false)));

joystick.R1.onTrue(
new InstantCommand(() -> setCurrentTrajectory(Robot.pathDown)).andThen(new WaitCommand(0.3))
.andThen(new FollowTrajectoryDemo(Robot.pathDown, this::setPosition))
);
joystick.getAxisAsButton(Axis.LEFT_TRIGGER)
.onTrue(
new InstantCommand(() -> setCurrentTrajectory(Robot.pathLeft)).andThen(new WaitCommand(0.3))
.andThen(new FollowTrajectoryDemo(Robot.pathLeft, this::setPosition))
);
joystick.L1.onTrue(
new InstantCommand(() -> setCurrentTrajectory(Robot.pathUp)).andThen(new WaitCommand(0.3))
.andThen(new FollowTrajectoryDemo(Robot.pathUp, this::setPosition))
);

joystick.START.onTrue(new InstantCommand(() -> setPosition(new Translation2d(0, 1), false)));
joystick.BACK.onTrue(new InstantCommand(() -> setPosition(new Translation2d(0, 1), true)));
}


Expand Down