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
14 changes: 13 additions & 1 deletion src/main/java/frc/robot/subsystems/ElevatorSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,13 @@

import com.revrobotics.spark.SparkFlex;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.sim.SparkFlexSim;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class ElevatorSubsystem extends SubsystemBase {
public class ElevatorSubsystem extends SubsystemBase implements AutoCloseable {
// motor (neo vortex according to co-engineering pres?)
private SparkFlex m_elevatorMotor = new SparkFlex(0, MotorType.kBrushless);
// pid
Expand Down Expand Up @@ -40,4 +42,14 @@ public void setPosition(double position) {
public void periodic() {
// This method will be called once per scheduler run
}

public SparkFlexSim getSimMotor() {
Copy link

Copilot AI Jan 6, 2025

Choose a reason for hiding this comment

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

The method getSimMotor() creates a new SparkFlexSim instance each time it is called. This might not be intended if the same instance is expected to be used throughout the tests. Consider storing the SparkFlexSim instance in a member variable and returning that instance.

Copilot uses AI. Check for mistakes.
return new SparkFlexSim(m_elevatorMotor,
DCMotor.getNeoVortex(1));
}

@Override
public void close() {
m_elevatorMotor.close();
}
}
50 changes: 50 additions & 0 deletions src/test/java/TestElevatorSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
import static org.junit.jupiter.api.Assertions.assertEquals;
import edu.wpi.first.hal.HAL;
import frc.robot.subsystems.ElevatorSubsystem;
import com.revrobotics.spark.SparkFlex;
import com.revrobotics.sim.SparkFlexSim;
import org.junit.jupiter.api.AfterEach;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;

public class TestElevatorSubsystem {
private ElevatorSubsystem m_elevatorSubsystem;
private SparkFlexSim m_simElevatorMotor;

@BeforeEach
public void setup() {
assert(HAL.initialize(500, 0));
m_elevatorSubsystem = new ElevatorSubsystem();
m_simElevatorMotor = m_elevatorSubsystem.getSimMotor();
}

@Test
public void testPower() {
assertEquals(m_simElevatorMotor.getAppliedOutput(), 0.0);
m_elevatorSubsystem.setPower(0.5);
assertEquals(m_simElevatorMotor.getAppliedOutput(), 0.5);
m_elevatorSubsystem.setPower(1.0);
assertEquals(m_simElevatorMotor.getAppliedOutput(), 1.0);
}

@Test void testPosition() {
assertEquals(m_simElevatorMotor.getSetpoint(), 0);
m_elevatorSubsystem.setPosition(0.5);
assertEquals(m_simElevatorMotor.getSetpoint(), 0.5);
m_elevatorSubsystem.setPosition(1.0);
assertEquals(m_simElevatorMotor.getSetpoint(), 1.0);
}

@Test void testPosition2() {
m_elevatorSubsystem.setPosition(1.0);
for (int i = 0; i < 100; i++) {
m_elevatorSubsystem.simulationPeriodic();
Copy link

Copilot AI Jan 6, 2025

Choose a reason for hiding this comment

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

The simulationPeriodic method is not defined in ElevatorSubsystem. It should be implemented to update the simulation state.

Suggested change
m_elevatorSubsystem.simulationPeriodic();
m_elevatorSubsystem.updateSimulationState();

Copilot uses AI. Check for mistakes.
}
assertEquals(m_simElevatorMotor.getPosition(), 1.0, 0.02);
}

@AfterEach
public void tearDown() {
m_elevatorSubsystem.close();
}
}