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

Get PDH current from singleton RobotContainer instance #96

Merged
merged 2 commits into from
Feb 16, 2024
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
11 changes: 6 additions & 5 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

package frc.robot;

import static frc.robot.RobotContainer.getRobotContainer;

import edu.wpi.first.wpilibj.DataLogManager;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.TimedRobot;
Expand All @@ -11,13 +13,12 @@
public class Robot extends TimedRobot {

private Command m_autonomousCommand;
private RobotContainer m_robotContainer;

@Override
public void robotInit() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();
getRobotContainer();

// Starts recording to data log
// https://docs.wpilib.org/en/stable/docs/software/telemetry/datalog.html#logging-joystick-data
Expand All @@ -28,7 +29,7 @@ public void robotInit() {
@Override
public void robotPeriodic() {
CommandScheduler.getInstance().run();
m_robotContainer.periodic();
getRobotContainer().periodic();
}

@Override
Expand All @@ -39,7 +40,7 @@ public void disabledPeriodic() {}

@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
m_autonomousCommand = getRobotContainer().getAutonomousCommand();

if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
Expand All @@ -55,7 +56,7 @@ public void teleopInit() {
m_autonomousCommand.cancel();
}

m_robotContainer.teleopInit();
getRobotContainer().teleopInit();
}

@Override
Expand Down
22 changes: 21 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,21 @@

public class RobotContainer {

private static RobotContainer INSTANCE = null;

public static RobotContainer getRobotContainer() {
if (INSTANCE == null) {
INSTANCE = new RobotContainer();
}
return INSTANCE;
}

private final PowerDistribution m_PowerDistribution = new PowerDistribution(1, ModuleType.kRev);

private final Drivetrain m_swerve = new Drivetrain();
private final Arm m_arm = new Arm();
private final Intake m_intake = new Intake();
private final Climber m_climber = new Climber(m_PowerDistribution);
private final Climber m_climber = new Climber();

private final EventLoop m_loop = new EventLoop();
private Joystick m_driver = new Joystick(OIConstants.kDriverControllerPort);
Expand Down Expand Up @@ -218,4 +227,15 @@ private int getSelectedAutonomousMode() {
}
return -1; // failure of the physical switch
}

/**
* Gets the current drawn from the Power Distribution Hub by a CAN motor controller, assuming that
* (PDH port number + 10) = CAN ID
*
* @param CANBusPort The CAN ID of the motor controller
* @return Current in Amps on the PDH channel corresponding to the motor channel
*/
public double getPDHCurrent(int CANBusPort) {
return m_PowerDistribution.getCurrent(CANBusPort - 10);
}
}
10 changes: 3 additions & 7 deletions src/main/java/frc/robot/climber/Climber.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.robot.climber;

import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj2.command.Command;
Expand All @@ -11,15 +10,12 @@ public class Climber extends SubsystemBase {

private ClimberSide[] m_actuators = new ClimberSide[2];

private final PowerDistribution m_pdp;

DifferentialDrive m_differentialDrive;

public Climber(PowerDistribution pdp) {
public Climber() {

this.m_pdp = pdp;
m_actuators[0] = new ClimberSide("Left", ClimberConstants.kLeftMotorPort, m_pdp);
m_actuators[1] = new ClimberSide("Right", ClimberConstants.kRightMotorPort, m_pdp);
m_actuators[0] = new ClimberSide("Left", ClimberConstants.kLeftMotorPort);
m_actuators[1] = new ClimberSide("Right", ClimberConstants.kRightMotorPort);

m_differentialDrive = new DifferentialDrive(m_actuators[0]::setPower, m_actuators[1]::setPower);
}
Expand Down
26 changes: 13 additions & 13 deletions src/main/java/frc/robot/climber/ClimberSide.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
package frc.robot.climber;

import static frc.robot.RobotContainer.getRobotContainer;

import com.revrobotics.CANSparkBase;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
Expand All @@ -10,7 +12,6 @@
import edu.wpi.first.math.filter.Debouncer.DebounceType;
import edu.wpi.first.math.filter.LinearFilter;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.Constants.ClimberConstants;
import frc.robot.Constants.ClimberConstants.CalibrationState;
Expand All @@ -36,15 +37,11 @@ public class ClimberSide {

private CalibrationState m_calibrationState = CalibrationState.UNCALIBRATED;

private final PowerDistribution m_pdp;

public ClimberSide(String climberName, int climberMotorChannel, PowerDistribution pdp) {
public ClimberSide(String climberName, int climberMotorChannel) {

this.climberName = climberName;
this.motorChannel = climberMotorChannel;

this.m_pdp = pdp;

m_climberMover = new CANSparkMax(motorChannel, MotorType.kBrushless);

m_climberMover.restoreFactoryDefaults();
Expand Down Expand Up @@ -102,7 +99,7 @@ public void resetEncoder() {
}

public boolean getCurrentSenseState() {
return m_debouncer.calculate(getSparkMaxCurrent() > ClimberConstants.kMotorCurrentHardStop);
return m_debouncer.calculate(getOutputCurrent() > ClimberConstants.kMotorCurrentHardStop);
}

private boolean getUpperSoftLimitSwtichState() {
Expand Down Expand Up @@ -143,14 +140,17 @@ private double getPosition() {
}

/**
* @return Current in Amps, output of linear filter
* @return Current in Amps, output of motor controller
*/
private double getSparkMaxCurrent() {
private double getOutputCurrent() {
return m_filter.calculate(m_climberMover.getOutputCurrent());
}

private double getPdhCurrent() {
return m_pdp.getCurrent(motorChannel - 10);
/**
* @return Current in Amps, input to motor controller
*/
private double getInputCurrent() {
return getRobotContainer().getPDHCurrent(motorChannel);
}

/**
Expand All @@ -166,8 +166,8 @@ public void periodic() {
getName() + "MotorRotations", getPosition() / ClimberConstants.kPositionConversionFactor);
SmartDashboard.putBoolean(getName() + "UpperSoftLimitState", getUpperSoftLimitSwtichState());
SmartDashboard.putBoolean(getName() + "LowerSoftLimitState", getLowerSoftLimitSwtichState());
SmartDashboard.putNumber(getName() + "SparkMaxCurrent", addPolarity(getSparkMaxCurrent()));
SmartDashboard.putNumber(getName() + "PDHCurrent", addPolarity(getPdhCurrent()));
SmartDashboard.putNumber(getName() + "OutputCurrent", addPolarity(getOutputCurrent()));
SmartDashboard.putNumber(getName() + "InputCurrent", addPolarity(getInputCurrent()));
SmartDashboard.putString(getName() + "CalibrationState", getCalibrationState().name());
}

Expand Down