Skip to content
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
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ public void runOpMode() {
launch = new LaunchControls(hardwareMap);
motors = new MotorConstructor(hardwareMap);
limelightCont = new LimelightControls(hardwareMap);
sorter = new SorterControls(motors);
sorter = new SorterControls(hardwareMap);
waitForStart();


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ public void runOpMode() {
launch = new LaunchControls(hardwareMap);
motors = new MotorConstructor(hardwareMap);
limelightCont = new LimelightControls(hardwareMap);
sorter = new SorterControls(motors);
sorter = new SorterControls(hardwareMap);
telemetry.addLine("Initialized. Waiting for start...");
telemetry.update();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ public void runOpMode() {
launch = new LaunchControls(hardwareMap);
motors = new MotorConstructor(hardwareMap);
limelightCont = new LimelightControls(hardwareMap);
sorter = new SorterControls(motors);
sorter = new SorterControls(hardwareMap);
telemetry.addLine("Initialized. Waiting for start...");
telemetry.update();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public void runOpMode() {
drive = new DriveControls(hardwareMap);
launch = new LaunchControls(hardwareMap);
motors = new MotorConstructor(hardwareMap);
sorter = new SorterControls(motors);
sorter = new SorterControls(hardwareMap);
intake = new IntakeControls(hardwareMap);


Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package org.firstinspires.ftc.teamcode.Utils_13233;

import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap;


public class SorterControls {
Expand All @@ -24,16 +25,16 @@ public class SorterControls {
// Motor Speed
float motorSpeed = 1.0f;

public SorterControls(MotorConstructor motors) {
this.motors = motors;
public SorterControls(HardwareMap hardwareMap) {
this.motors = new MotorConstructor(hardwareMap);
}

/**
* Move the sorter to a position to intake from
*
* @param pos Enum to determine what positon to move to
*/
private void moveToIntakePos(intakePos pos) {
public void moveToIntakePos(intakePos pos) {
switch (pos) {
case INTAKE_POS_1:
motors.Sorter.setTargetPosition(intakePos1);
Expand All @@ -59,7 +60,7 @@ private void moveToIntakePos(intakePos pos) {
*
* @param pos Enum to determine what positon to move to
*/
private void moveToLaunchPos(launchPos pos) {
public void moveToLaunchPos(launchPos pos) {
switch (pos) {
case LAUNCH_POS_1:
motors.Sorter.setTargetPosition(LaunchPos1);
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,262 @@
package org.firstinspires.ftc.teamcode;

import static org.junit.jupiter.api.Assertions.assertThrows;
import static org.mockito.Mockito.verify;

import com.qualcomm.robotcore.hardware.DcMotor;

import org.firstinspires.ftc.teamcode.Utils_13233.SorterControls;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.DisplayName;
import org.junit.jupiter.api.Test;

public class SorterControlsTest {
public SorterControls sorter;

MockMotorUtil mockMotor = new MockMotorUtil();

@BeforeEach
void motorSetup() {
mockMotor.setUp();
sorter = new SorterControls(mockMotor.hardwareMap);
}


// Test Move to intake position
@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveToIntakePos_pos1() {
sorter.moveToIntakePos(SorterControls.intakePos.INTAKE_POS_1);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos1);
}

@DisplayName("should set the sorter to the intake position 2")
@Test
void testMoveToIntakePos_pos2() {
sorter.moveToIntakePos(SorterControls.intakePos.INTAKE_POS_2);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos2);
}

@DisplayName("should set the sorter to the intake position 3")
@Test
void testMoveToIntakePos_pos3() {
sorter.moveToIntakePos(SorterControls.intakePos.INTAKE_POS_3);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos3);
}


// Test Move to launch position
@DisplayName("should set the sorter to the launch position 1")
@Test
void testMoveToLaunchPos_pos1() {
sorter.moveToLaunchPos(SorterControls.launchPos.LAUNCH_POS_1);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos1);
}

@DisplayName("should set the sorter to the launch position 2")
@Test
void testMoveToLaunchPos_pos2() {
sorter.moveToLaunchPos(SorterControls.launchPos.LAUNCH_POS_2);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos2);
}

@DisplayName("should set the sorter to the launch position 3")
@Test
void testMoveToLaunchPos_pos3() {
sorter.moveToLaunchPos(SorterControls.launchPos.LAUNCH_POS_3);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos3);
}


// Test Move to sorter position
@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSorterToPos_intake_pos1() {
sorter.moveSorterToPos(SorterControls.sorterModes.INTAKE, 1);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos1);
}

// Test Move to sorter position
@DisplayName("should set the sorter to the intake position 2")
@Test
void testMoveSorterToPos_intake_pos2() {
sorter.moveSorterToPos(SorterControls.sorterModes.INTAKE, 2);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos2);
}

// Test Move to sorter position
@DisplayName("should set the sorter to the intake position 3")
@Test
void testMoveSorterToPos_intake_pos3() {
sorter.moveSorterToPos(SorterControls.sorterModes.INTAKE, 3);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos3);
}

@DisplayName("should throw a runtime exception")
@Test
void testMoveSorterToPos_intake_runtimeException() {
assertThrows(RuntimeException.class, () -> {
sorter.moveSorterToPos(SorterControls.sorterModes.INTAKE, 4);
});
}

@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSorterToPos_launch_pos1() {
sorter.moveSorterToPos(SorterControls.sorterModes.LAUNCH, 1);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos1);
}

// Test Move to sorter position
@DisplayName("should set the sorter to the intake position 2")
@Test
void testMoveSorterToPos_launch_pos2() {
sorter.moveSorterToPos(SorterControls.sorterModes.LAUNCH, 2);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos2);
}

// Test Move to sorter position
@DisplayName("should set the sorter to the intake position 3")
@Test
void testMoveSorterToPos_launch_pos3() {
sorter.moveSorterToPos(SorterControls.sorterModes.LAUNCH, 3);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos3);
}

@DisplayName("should throw a runtime exception")
@Test
void testMoveSorterToPos_launch_runtimeException() {
assertThrows(RuntimeException.class, () -> {
sorter.moveSorterToPos(SorterControls.sorterModes.LAUNCH, 4);
});
}

@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSimpleSorterToPos_intake_pos1() {
sorter.simpleSorterPosition(true, false,
false, SorterControls.sorterModes.INTAKE);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos1);
}

@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSimpleSorterToPos_intake_pos2() {
sorter.simpleSorterPosition(false, true,
false, SorterControls.sorterModes.INTAKE);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos2);
}

@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSimpleSorterToPos_intake_pos3() {
sorter.simpleSorterPosition(false, false,
true, SorterControls.sorterModes.INTAKE);

verify(mockMotor.Sorter).setTargetPosition(sorter.intakePos3);
}

@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSimpleSorterToPos_launch_pos1() {
sorter.simpleSorterPosition(true, false,
false, SorterControls.sorterModes.LAUNCH);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos1);
}

@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSimpleSorterToPos_launch_pos2() {
sorter.simpleSorterPosition(false, true,
false, SorterControls.sorterModes.LAUNCH);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos2);
}

@DisplayName("should set the sorter to the intake position 1")
@Test
void testMoveSimpleSorterToPos_launch_pos3() {
sorter.simpleSorterPosition(false, false,
true, SorterControls.sorterModes.LAUNCH);

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos3);
}

@DisplayName("should set the sorter to the launch position 1")
@Test
void testMoveGreenToLaunchPos_1() {
sorter.currentSorterStates[0] = SorterControls.ballColors.GREEN;

sorter.moveGreenToLaunchPos();

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos1);
}

@DisplayName("should set the sorter to the launch position 1")
@Test
void testMoveGreenToLaunchPos_2() {
sorter.currentSorterStates[1] = SorterControls.ballColors.GREEN;

sorter.moveGreenToLaunchPos();

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos2);
}

@DisplayName("should set the sorter to the launch position 1")
@Test
void testMoveGreenToLaunchPos_3() {
sorter.currentSorterStates[2] = SorterControls.ballColors.GREEN;

sorter.moveGreenToLaunchPos();

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos3);
}

@DisplayName("should set the sorter to the launch position 1")
@Test
void testMovePurpleToLaunchPos_1() {
sorter.currentSorterStates[0] = SorterControls.ballColors.PURPLE;

sorter.moveToPurpleLaunchPos();

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos1);
}

@DisplayName("should set the sorter to the launch position 1")
@Test
void testMovePurpleToLaunchPos_2() {
sorter.currentSorterStates[1] = SorterControls.ballColors.PURPLE;

sorter.moveToPurpleLaunchPos();

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos2);
}

@DisplayName("should set the sorter to the launch position 1")
@Test
void testMovePurpleToLaunchPos_3() {
sorter.currentSorterStates[0] = SorterControls.ballColors.NULL;
sorter.currentSorterStates[1] = SorterControls.ballColors.NULL;
sorter.currentSorterStates[2] = SorterControls.ballColors.PURPLE;

sorter.moveToPurpleLaunchPos();

verify(mockMotor.Sorter).setTargetPosition(sorter.LaunchPos3);
}
}