Skip to content
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
18 changes: 16 additions & 2 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,9 @@
import frc.robot.SubsystemChecker.SubsystemType;
import frc.robot.commands.BrakeModeDisabled;
import frc.robot.commands.CheckArmSetpoints;
import frc.robot.commands.SetBlingCommand;
import frc.robot.commands.SyncArmEncoders;
import frc.robot.commands.SyncArmEncodersV2;
import frc.robot.commands.SyncSteerEncoders;
import frc.robot.config.Config;
import frc.robot.robotcontainers.ArmBotContainer;
Expand All @@ -30,6 +32,7 @@
import frc.robot.robotcontainers.MiniNeoDiffContainer;
import frc.robot.robotcontainers.MiniSwerveContainer;
import frc.robot.robotcontainers.RobotContainer;
import frc.robot.subsystems.BlingSubsystem;
import frc.robot.subsystems.DiffNeoSubsystem;
import frc.robot.subsystems.DiffTalonSubsystem;

Expand All @@ -46,6 +49,8 @@ public class Robot extends TimedRobot {

Compressor pcmCompressor = new Compressor(1, PneumaticsModuleType.CTREPCM);

private boolean m_firstDisableAtBootup = true;




Expand Down Expand Up @@ -97,8 +102,9 @@ public void robotInit() {
}

if (SubsystemChecker.canSubsystemConstruct(SubsystemType.SwerveSubsystem)) {
BlingSubsystem.getINSTANCE().setRed();
new SyncSteerEncoders().schedule();
new WaitCommand(3).andThen(new SyncArmEncoders()).schedule();
// new SyncArmEncodersV2().schedule(); // With new encoder wiring, no longer need to sync arms
}

// Add CommandScheduler to shuffleboard so we can display what commands are scheduled
Expand Down Expand Up @@ -131,7 +137,15 @@ public void robotPeriodic() {
@Override
public void disabledInit() {
if (brakeModeDisabledCommand != null)
brakeModeDisabledCommand.schedule();
brakeModeDisabledCommand.schedule();

if (SubsystemChecker.canSubsystemConstruct(SubsystemType.BlingSubsystem)) {
if (m_firstDisableAtBootup) {
m_firstDisableAtBootup = false;
} else {
BlingSubsystem.getINSTANCE().setDisabled();
}
}
}

@Override
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/SubsystemChecker.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,12 @@ public enum SubsystemType {
*/
// RobotID: 0, 2023 Competition robot, unnamed
private static SubsystemType[] compBotId0 = new SubsystemType[] {
SubsystemType.SwerveSubsystem, // Chassis unknown
SubsystemType.SwerveSubsystem,
SubsystemType.ArmSubsystem,
SubsystemType.RelaySubsystem,
SubsystemType.VisionNTSubsystem,
SubsystemType.GripperSubsystem,
SubsystemType.BlingSubsystem,
};

// RobotID: 1, 2022 robot, RapidReact, Clutch
Expand Down
150 changes: 150 additions & 0 deletions src/main/java/frc/robot/commands/SyncArmEncodersV2.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,150 @@
// 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.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.config.ArmConfig;
import frc.robot.subsystems.ArmSubsystem;
import frc.robot.subsystems.BlingSubsystem;

public class SyncArmEncodersV2 extends CommandBase {
private Timer m_smallTimer = new Timer();
private Timer m_permanantTimer = new Timer();
private int m_commandState = 0;
private int m_numSamples = 0;
private double m_sumBotSamples = 0;
private double m_sumTopSamples = 0;

/** Creates a new SyncSteerEncoders. */
public SyncArmEncodersV2() {
addRequirements(ArmSubsystem.getInstance());
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
m_smallTimer.restart();
m_permanantTimer.restart();
m_numSamples = 0;
m_sumBotSamples = 0;
m_sumTopSamples = 0;
m_commandState = 0;

BlingSubsystem.getINSTANCE().noEncodersSynced();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if (m_smallTimer.get() > ArmConfig.ENCODER_SYNCING_PERIOD_V2) {
m_smallTimer.reset();

if (m_commandState == 0 && m_permanantTimer.hasElapsed(1)) {
DriverStation.reportWarning(
String.format("Arm encoders are not synced, collecting arm encoder samples... (%.1fs)", m_permanantTimer.get()),
false);

m_commandState = 1;

} else if (m_commandState == 1) {
m_sumBotSamples += ArmSubsystem.getInstance().getAbsoluteBottom();
m_sumTopSamples += ArmSubsystem.getInstance().getAbsoluteTop();
m_numSamples++;

if (m_numSamples >= ArmConfig.NUM_SYNCING_SAMPLES) {
m_commandState = 2;
}
} else if (m_commandState == 2) {
ArmSubsystem.getInstance().resetEncoder(
m_sumBotSamples / m_numSamples,
m_sumTopSamples / m_numSamples
);

if (ArmSubsystem.getInstance().areEncodersSynced() == false) {
DriverStation.reportWarning(
String.format("Arm encoders are not synced, attempting to sync them... (%.1fs)", m_permanantTimer.get()),
false);

} else {
m_commandState = 99; // End the command, the encoders are synced
}
}
}
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
if (m_commandState == 99) {
DriverStation.reportWarning(
String.format("Arm encoders are synced (%.1f) \n", m_permanantTimer.get()),
false);

BlingSubsystem.getINSTANCE().armEncodersSynced();

new WaitCommand(1).andThen(
Commands.runOnce(() -> BlingSubsystem.getINSTANCE().armEncodersSynced()),
new WaitCommand(1),
Commands.runOnce(() -> BlingSubsystem.getINSTANCE().armEncodersSynced())
).schedule();

ArmSubsystem.getInstance().sparkMaxBurnFlash();
}

m_permanantTimer.stop();
m_smallTimer.stop();

if (
/** Temporary checks for current encoder setup. TODO: Remove once encoder wrapping is solved.*/
ArmSubsystem.getInstance().getBottomPosition() < Math.toRadians(5) ||
ArmSubsystem.getInstance().getBottomPosition() > Math.toRadians(170) ||
ArmSubsystem.getInstance().getTopPosition() < Math.toRadians(5) ||
ArmSubsystem.getInstance().getTopPosition() > Math.toRadians(70) ||
ArmSubsystem.getInstance().areEncodersSynced() == false ||
m_commandState != 99
) {

DriverStation.reportError("Arm encoders were reset outside the proper range. " +
" Disabling the arm to prevent damage." +
" Make sure the code boots up with the arm in the reset position.", true);

// This line below will prevent any commands from being scheduled to the ArmSubsystem.
// This line is temporary while we haven't properly setup the absolute encoders properly yet.
// If it's blocking you from using the arm, you just need to put the arm in the reset position
// and reboot the code (which will properly reset the NEO encoders the absolute encoders).
Commands.run(() -> ArmSubsystem.getInstance(), ArmSubsystem.getInstance()).withInterruptBehavior(InterruptionBehavior.kCancelIncoming).ignoringDisable(true).schedule();
}
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
if (m_permanantTimer.get() > ArmConfig.ENCODER_SYNCING_TIMEOUT) {
DriverStation.reportError(
String.format("Arm encoders are not synced. SyncArmEncodersV2 spent %.1fs trying to sync them and has timed out",
m_permanantTimer.get()),
false);

return true;
}
return m_commandState == 99;
}

@Override
public boolean runsWhenDisabled() {
return true;
}

@Override
public InterruptionBehavior getInterruptionBehavior() {
DriverStation.reportWarning("Another ArmSubsystem command was scheduled while " +
"SyncArmEncodersV2 is still running. Cancelling the incoming command.", false);
return InterruptionBehavior.kCancelIncoming;
}
}
20 changes: 13 additions & 7 deletions src/main/java/frc/robot/commands/SyncSteerEncoders.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ public void initialize() {
@Override
public void execute() {
SmartDashboard.putNumber("SyncSteerState", state);
if (state == 0 && m_permanantTimer.hasElapsed(6)) {
if (state == 0 && m_permanantTimer.hasElapsed(1)) {
state = 1;
DriverStation.reportWarning(
String.format("Starting to sync steer encoders (%.1fs)", m_permanantTimer.get()), false);
Expand All @@ -57,14 +57,16 @@ public void execute() {
false);
SwerveSubsystem.getInstance().resetEncodersFromCanCoder();
} else {
state = 2;
state = 99;
m_smallTimer.restart();
}
}
if (state == 2 && m_smallTimer.hasElapsed(5)) {
SwerveSubsystem.getInstance().resetEncodersFromCanCoder();
state = 99;
}
// if (state == 2 && m_smallTimer.hasElapsed(1)) {
// if (SwerveSubsystem.getInstance().checkSteeringEncoders() == false) {
// SwerveSubsystem.getInstance().resetEncodersFromCanCoder();
// }
// state = 99;
// }
SmartDashboard.putNumber("SyncSteerState", state);
}

Expand All @@ -77,7 +79,11 @@ public void end(boolean interrupted) {
false);
BlingSubsystem.getINSTANCE().steerEncodersSynced();

new WaitCommand(1).andThen(Commands.runOnce(() -> BlingSubsystem.getINSTANCE().steerEncodersSynced())).schedule();
new WaitCommand(1).andThen(
Commands.runOnce(() -> BlingSubsystem.getINSTANCE().steerEncodersSynced()),
new WaitCommand(1),
Commands.runOnce(() -> BlingSubsystem.getINSTANCE().steerEncodersSynced())
).schedule();
}

m_permanantTimer.stop();
Expand Down
14 changes: 9 additions & 5 deletions src/main/java/frc/robot/config/ArmConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,8 @@ public enum ArmPosition {
GAME_PIECE_BOTTOM
}

public static final double TOP_NEO_GEAR_RATIO = Config.robotSpecific(23.5, 0.0, 0.0, 0.0, 0.0, 60.0, 60.0); //comp --> 23.5
public static final double BOTTOM_NEO_GEAR_RATIO = 62.5;
public static final double TOP_NEO_GEAR_RATIO = Config.robotSpecific(1.0, 0.0, 0.0, 0.0, 0.0, 60.0, 60.0); // NEO Encoder gear ratio is 23.5;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

  1. Suggest to have a different name to avoid confusion, i.e., don't use NEO_GEAR_RATIO.
  2. Why original top and bottom gear ratios are different?

public static final double BOTTOM_NEO_GEAR_RATIO = 1.0; // NEO Encoder gear ratio is 62.5;
public static final double L1 = 27.75; //length of arm 1 in inches
public static final double L2 = 38.6; //length of arm 2 in inches
public static final double LENGTH_BOTTOM_ARM_TO_COG = 14.56;
Expand Down Expand Up @@ -198,12 +198,16 @@ public enum ArmPosition {
public static final int top_duty_cycle_channel = 9;
public static final int bottom_duty_cycle_channel = 7;

// arm offsets
public static final double top_arm_offset = -282.000000;
public static final double bottom_arm_offset = 307.800000;
// arm offsets - Must be [0, 360] if using setZeroOffset on a REV AbsoluteEncoder object
public static final double top_arm_offset = 285; // Old rio wiring: -282.000000;
public static final double bottom_arm_offset = 50.2; // Old rio wiring: 307.800000;

public static final boolean botEncoderInverted = true;
public static final boolean topEncoderInverted = false;

// Syncing encoders
public static double ENCODER_SYNCING_PERIOD = 0.4; // seconds
public static double ENCODER_SYNCING_PERIOD_V2 = 0.05; // seconds
public static int ENCODER_SYNCING_TIMEOUT = 20; // seconds
public static double ENCODER_SYNCING_TOLERANCE = 0.01; // radians
public static int NUM_SYNCING_SAMPLES = 20; // num of samples needed to average
Expand Down
11 changes: 7 additions & 4 deletions src/main/java/frc/robot/config/Config.java
Original file line number Diff line number Diff line change
Expand Up @@ -208,13 +208,16 @@ public static class Swerve{

// ~ Teleop speeds. Speeds should be portional to kMaxAttainableAngularSpeed. Angular speeds should be specified.

// REDUCING THE SPEED OF THE ROBOT SO WE DON"T DAMAGE SPONSER'S CARPET
public static final double OUTREACH_SPEED_REDUCTION = 0.4;

// Default Speeds
public static final double teleopDefaultSpeed = kMaxAttainableWheelSpeed;// Full speed
public static final double teleopDefaultAngularSpeed = Math.PI*3.0; // Old value: Math.PI*2.0
public static final double teleopDefaultSpeed = kMaxAttainableWheelSpeed * OUTREACH_SPEED_REDUCTION;// Full speed
public static final double teleopDefaultAngularSpeed = Math.PI*3.0 * OUTREACH_SPEED_REDUCTION; // Old value: Math.PI*2.0

// Left Bumper speeds
public static final double teleopLeftBumperSpeed = kMaxAttainableWheelSpeed / 3.0;// A third of full speed
public static final double teleopLeftBumperAngularSpeed = Math.PI; // Can be a slower angular speed if wanted
public static final double teleopLeftBumperSpeed = kMaxAttainableWheelSpeed / 3.0 * OUTREACH_SPEED_REDUCTION;// A third of full speed
public static final double teleopLeftBumperAngularSpeed = Math.PI * OUTREACH_SPEED_REDUCTION; // Can be a slower angular speed if wanted

// Right bumper speeds
public static final double teleopRightBumperSpeed = 0.3;
Expand Down
Loading