Skip to content

Commit

Permalink
Remove unnecessary files, adding mechanism classes to separate out me…
Browse files Browse the repository at this point in the history
…chanism functionality
  • Loading branch information
CoryNessCTR committed Dec 8, 2023
1 parent dd8085f commit 1cdd898
Show file tree
Hide file tree
Showing 28 changed files with 262 additions and 739 deletions.
13 changes: 2 additions & 11 deletions java/BasicLatencyCompensation/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,6 @@
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.Pigeon2;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.sim.CANcoderSimState;
import com.ctre.phoenix6.sim.Pigeon2SimState;
import com.ctre.phoenix6.sim.TalonFXSimState;

import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
Expand All @@ -26,16 +23,10 @@
public class Robot extends TimedRobot {
private final String CANBUS_NAME = "Fred";
private CANcoder m_cc = new CANcoder(0, CANBUS_NAME);
private TalonFX m_fx = new TalonFX(0, CANBUS_NAME);
private TalonFX m_fx = new TalonFX(0, CANBUS_NAME);
private Pigeon2 m_p2 = new Pigeon2(0, CANBUS_NAME);
private int m_printCount = 0;

//TODO finish creating simulation objects
private CANcoderSimState m_ccSim = m_cc.getSimState();
private TalonFXSimState m_fxSim = m_fx.getSimState();
private Pigeon2SimState m_p2Sim = m_p2.getSimState();


private DutyCycleOut m_dutycycle = new DutyCycleOut(0);

XboxController m_joystick = new XboxController(0);
Expand All @@ -60,7 +51,7 @@ public class Robot extends TimedRobot {
*/
@Override
public void robotInit() {

}

@Override
Expand Down
9 changes: 0 additions & 9 deletions java/CANcoder/simgui.json
Original file line number Diff line number Diff line change
@@ -1,13 +1,4 @@
{
"HALProvider": {
"Other Devices": {
"CANCoder (Pro)[1]": {
"header": {
"open": true
}
}
}
},
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo",
Expand Down
43 changes: 43 additions & 0 deletions java/CANcoder/src/main/java/frc/robot/Mechanisms.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package frc.robot;

import com.ctre.phoenix6.StatusSignal;

import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj.util.Color8Bit;

/**
* Class to keep all the mechanism-specific objects together and out of the main example
*/
public class Mechanisms {
private final double HEIGHT = 1;
private final double WIDTH = 1;
private final double ROOT_X = WIDTH / 2;
private final double ROOT_Y = HEIGHT / 2;

private Mechanism2d mech = new Mechanism2d(WIDTH, HEIGHT); // Main mechanism object
private MechanismLigament2d wrist = mech.getRoot("base", ROOT_X, ROOT_Y)
.append(new MechanismLigament2d("Wrist", .25, 90, 6, new Color8Bit(Color.kAliceBlue)));

@SuppressWarnings("unused")
private MechanismLigament2d leftArrow = wrist.append(
new MechanismLigament2d("LeftArrow",
0.1,
150,
6,
new Color8Bit(Color.kAliceBlue)));
@SuppressWarnings("unused")
private MechanismLigament2d rightArrow = wrist.append(
new MechanismLigament2d("RightArrow",
0.1,
-150,
6,
new Color8Bit(Color.kAliceBlue)));

public void update(StatusSignal<Double> angle) {
SmartDashboard.putData("mech2d", mech); // Creates a mech2d window in GUI
wrist.setAngle(angle.getValue() * 360); // Converts 1 rotation to 360 degrees
}
}
35 changes: 5 additions & 30 deletions java/CANcoder/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,6 @@
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj.util.Color8Bit;
import frc.robot.sim.PhysicsSim;

/**
Expand All @@ -35,21 +30,8 @@ public class Robot extends TimedRobot {
private final XboxController controller = new XboxController(0);

double currentTime = Timer.getFPGATimestamp();

/* Mech2d only */
private final double HEIGHT = 1;
private final double WIDTH = 1;
private final double ROOT_X = WIDTH / 2;
private final double ROOT_Y = HEIGHT / 2;

private Mechanism2d mech = new Mechanism2d(WIDTH, HEIGHT); // Main mechanism object
private MechanismLigament2d wrist = mech.
getRoot("base", ROOT_X, ROOT_Y).
append(new MechanismLigament2d("Wrist", .25, 90, 6, new Color8Bit(Color.kAliceBlue)));

private MechanismLigament2d leftArrow = wrist.append(new MechanismLigament2d("LeftArrow", 0.1, 150, 6, new Color8Bit(Color.kAliceBlue)));
private MechanismLigament2d rightArrow = wrist.append(new MechanismLigament2d("RightArrow", 0.1, -150, 6, new Color8Bit(Color.kAliceBlue)));
/* End mech2d only */

private final Mechanisms mechanism = new Mechanisms();

/**
* This function is run when the robot is first started up and should be used for any
Expand Down Expand Up @@ -107,8 +89,7 @@ public void robotPeriodic() {
*/
System.out.println();
}
SmartDashboard.putData("mech2d", mech); // Creates a mech2d window in GUI
wrist.setAngle(cancoder.getPosition().getValue()*360); // Converts 1 rotation to 360 degrees
mechanism.update(cancoder.getPosition());
}

@Override
Expand All @@ -125,18 +106,12 @@ public void teleopInit() {
cancoder.setPosition(0.4, 0.1); // Set our position to .4 rotations and wait up to 100 ms for the setter to take affect
cancoder.getPosition().waitForUpdate(0.1); // And wait up to 100 ms for the position to take affect
System.out.println("Set the position to 0.4 rotations, we are currently at " + cancoder.getPosition()); // Use java's implicit toString operator

}

@Override
public void teleopPeriodic() {
var fwd = controller.getLeftY();

//modify control requests
fwdOut.Output = fwd;

//send control requests
talonFX.setControl(fwdOut);
/* Send control requests to control Talon that's connected to CANcoder */
talonFX.setControl(fwdOut.withOutput(controller.getLeftY()));
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ public TalonFXSimProfile(final TalonFX falcon, final CANcoder canCoder, final do
*/
public void run() {
// DEVICE SPEED SIMULATION

_motorSim.setInputVoltage(_falcon.getSimState().getMotorVoltage());

_motorSim.update(getPeriod());
Expand Down
2 changes: 1 addition & 1 deletion java/CurrentLimits/src/test/java/CurrentLimitTests.java
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ public void robotIsEnabled() {
/* verify that the robot is enabled */
assertTrue(DriverStation.isEnabled());
}
//TODO add simulation compatibility to the bolow java code

@Test
public void testStatorLimit() {
var statorCurrent = talon.getStatorCurrent();
Expand Down
1 change: 0 additions & 1 deletion java/FusedCANcoder/networktables.json

This file was deleted.

92 changes: 0 additions & 92 deletions java/FusedCANcoder/simgui-ds.json

This file was deleted.

57 changes: 0 additions & 57 deletions java/FusedCANcoder/simgui.json

This file was deleted.

Loading

0 comments on commit 1cdd898

Please sign in to comment.