Skip to content
This repository has been archived by the owner on Jan 10, 2024. It is now read-only.

Tank limit widget #52

Open
wants to merge 7 commits into
base: master
Choose a base branch
from
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
1 change: 1 addition & 0 deletions .java-version
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
temurin64-17.0.5
31 changes: 30 additions & 1 deletion src/main/java/frc/robot/subsystems/Tank.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,10 @@
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.shuffleboard.*;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
Expand All @@ -24,21 +26,26 @@ public class Tank extends SubsystemBase {
public DifferentialDrive drive;

public boolean brakeMode;

private GenericEntry stallWidget;
private GenericEntry freeWidget;
private int stallLimit;
private int freeLimit;
/** */
public Tank() {
if (CanConstants.kBaseType == "tank") {
leftFront = new CANSparkMax(Constants.CanConstants.kLeftFrontMotorPort, MotorType.kBrushless);
leftFront.restoreFactoryDefaults();
leftFront.setInverted(true);
leftFront.setIdleMode(IdleMode.kCoast);
leftFront.setSmartCurrentLimit(40);
leftFront.setOpenLoopRampRate(Constants.CanConstants.kRampRate);
leftFront.burnFlash();

leftRear = new CANSparkMax(Constants.CanConstants.kLeftRearMotorPort, MotorType.kBrushless);
leftRear.restoreFactoryDefaults();
leftRear.setInverted(true);
leftRear.setIdleMode(IdleMode.kCoast);
leftRear.setSmartCurrentLimit(40);
leftRear.setOpenLoopRampRate(Constants.CanConstants.kRampRate);
leftRear.burnFlash();

Expand All @@ -50,13 +57,15 @@ public Tank() {
rightFront.restoreFactoryDefaults();
rightFront.setInverted(false);
rightFront.setIdleMode(IdleMode.kCoast);
rightFront.setSmartCurrentLimit(40);
rightFront.setOpenLoopRampRate(Constants.CanConstants.kRampRate);
rightFront.burnFlash();

rightRear = new CANSparkMax(Constants.CanConstants.kRightRearMotorPort, MotorType.kBrushless);
rightRear.restoreFactoryDefaults();
rightRear.setInverted(false);
rightRear.setIdleMode(IdleMode.kCoast);
rightRear.setSmartCurrentLimit(40);
rightRear.setOpenLoopRampRate(Constants.CanConstants.kRampRate);
rightRear.burnFlash();

Expand All @@ -76,6 +85,17 @@ public Tank() {
brakeMode = false;
SmartDashboard.putBoolean("brakeMode", brakeMode);

// create a new slider widget for the current limits
stallWidget =
Shuffleboard.getTab("Config")
.add("Stall Limit", 40)
.withWidget(BuiltInWidgets.kNumberSlider)
.getEntry();
freeWidget =
Shuffleboard.getTab("Config")
.add("Free Limit", 40)
.withWidget(BuiltInWidgets.kNumberSlider)
.getEntry();
leftFront.setSmartCurrentLimit(40, 60);
leftRear.setSmartCurrentLimit(40, 60);
rightFront.setSmartCurrentLimit(40, 60);
Expand All @@ -87,6 +107,15 @@ public Tank() {
public void periodic() {
SmartDashboard.putNumber("leftStickY", RobotContainer.getLeftStickY());
SmartDashboard.putNumber("rightStickX", RobotContainer.getRightStickX());

// set all four motors to the stall and free limit widget values
stallLimit = (int) stallWidget.getDouble(10);
freeLimit = (int) freeWidget.getDouble(40);

leftFront.setSmartCurrentLimit(stallLimit, freeLimit);
leftRear.setSmartCurrentLimit(stallLimit, freeLimit);
rightFront.setSmartCurrentLimit(stallLimit, freeLimit);
rightRear.setSmartCurrentLimit(stallLimit, freeLimit);
}

/**
Expand Down
44 changes: 24 additions & 20 deletions src/main/java/frc/robot/subsystems/Vision.java
Original file line number Diff line number Diff line change
@@ -1,33 +1,21 @@
package frc.robot.subsystems;

import com.revrobotics.ColorSensorV3;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.I2C;
import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import org.photonvision.PhotonCamera;
import org.photonvision.targeting.PhotonPipelineResult;
import java.lang.reflect.Array;

public class Vision extends SubsystemBase {
private PhotonCamera limelight;
private ColorSensorV3 colorSensor;

// Constants such as camera and target height stored. Change per robot and goal!

final double CAMERA_HEIGHT_METERS = Units.inchesToMeters(24);

final double TARGET_HEIGHT_METERS = Units.feetToMeters(5);

// Angle between horizontal and the camera.

final double CAMERA_PITCH_RADIANS = Units.degreesToRadians(0);

NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
// Pipeline mode.
public static final String kLimelightPipelineKey = "limelight-pipeline";

public Vision() {
// Stuff goes here
limelight = new PhotonCamera("limelight");
colorSensor = new ColorSensorV3(I2C.Port.kOnboard);
// Set default pipeline
if (!Preferences.containsKey(kLimelightPipelineKey)) {
Expand All @@ -47,12 +35,28 @@ public void simulationPeriodic() {
}

/**
* Get the latest pipeline result.
* Get the selected property from the NetworkTable.
*
* @return The latest pipeline result.
* @param property The property to fetch.
* @return The fetched property.
*/
public PhotonPipelineResult getLatestResult() {
return limelight.getLatestResult();
public Array[]
getProperties() { // we don't know what type we return until we process it in the if statement
// //
var tx = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tx").getDouble(0);
var ty = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ty").getDouble(0);
var tv = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tv").getDouble(0);
var ta = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ta").getDouble(0);
var tl = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tl").getDouble(0);
var cl = NetworkTableInstance.getDefault().getTable("limelight").getEntry("cl").getDouble(0);
var tshort =
NetworkTableInstance.getDefault().getTable("limelight").getEntry("tshort").getDouble(0);
var tlong =
NetworkTableInstance.getDefault().getTable("limelight").getEntry("tlong").getDouble(0);
var thor =
NetworkTableInstance.getDefault().getTable("limelight").getEntry("thor").getDouble(0);
var tvert =
NetworkTableInstance.getDefault().getTable("limelight").getEntry("tvert").getDouble(0);
}

/**
Expand Down
Loading