Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/Train' into Train
Browse files Browse the repository at this point in the history
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/LearningTeleOp.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/TrumanLearnsTeleOP.java
  • Loading branch information
ntt305 committed Oct 10, 2024
2 parents 391987c + 465bf44 commit b561675
Show file tree
Hide file tree
Showing 33 changed files with 298 additions and 91 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@
public class BasicOmniOpMode_Linear extends LinearOpMode {

// Declare OpMode members for each of the 4 motors.
private ElapsedTime runtime = new ElapsedTime();
private final ElapsedTime runtime = new ElapsedTime();
private DcMotor leftFrontDrive = null;
private DcMotor leftBackDrive = null;
private DcMotor rightFrontDrive = null;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
public class BasicOpMode_Iterative extends OpMode
{
// Declare OpMode members.
private ElapsedTime runtime = new ElapsedTime();
private final ElapsedTime runtime = new ElapsedTime();
private DcMotor leftDrive = null;
private DcMotor rightDrive = null;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
public class BasicOpMode_Linear extends LinearOpMode {

// Declare OpMode members.
private ElapsedTime runtime = new ElapsedTime();
private final ElapsedTime runtime = new ElapsedTime();
private DcMotor leftDrive = null;
private DcMotor rightDrive = null;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,7 @@ private boolean setManualExposure(int exposureMS, int gain) {
exposureControl.setMode(ExposureControl.Mode.Manual);
sleep(50);
}
exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS);
exposureControl.setExposure(exposureMS, TimeUnit.MILLISECONDS);
sleep(20);

// Set Gain.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,9 @@ public void runOpMode() {
// Each time around the loop, the servos will move by a small amount.
// Limit the total offset to half of the full travel range
if (gamepad1.right_bumper)
handOffset += robot.HAND_SPEED;
handOffset += RobotHardware.HAND_SPEED;
else if (gamepad1.left_bumper)
handOffset -= robot.HAND_SPEED;
handOffset -= RobotHardware.HAND_SPEED;
handOffset = Range.clip(handOffset, -0.5, 0.5);

// Move both servos to new position. Use RobotHardware class
Expand All @@ -114,9 +114,9 @@ else if (gamepad1.left_bumper)
// Use gamepad buttons to move arm up (Y) and down (A)
// Use the MOTOR constants defined in RobotHardware class.
if (gamepad1.y)
arm = robot.ARM_UP_POWER;
arm = RobotHardware.ARM_UP_POWER;
else if (gamepad1.a)
arm = robot.ARM_DOWN_POWER;
arm = RobotHardware.ARM_DOWN_POWER;
else
arm = 0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
@Disabled
public class ConceptNullOp extends OpMode {

private ElapsedTime runtime = new ElapsedTime();
private final ElapsedTime runtime = new ElapsedTime();

/**
* This method will be called once, when the INIT button is pressed.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@
public class ConceptRevSPARKMini extends LinearOpMode {

// Declare OpMode members.
private ElapsedTime runtime = new ElapsedTime();
private final ElapsedTime runtime = new ElapsedTime();
private DcMotorSimple leftDrive = null;
private DcMotorSimple rightDrive = null;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,9 @@
public class ConceptSoundsOnBotJava extends LinearOpMode {

// Point to sound files on the phone's drive
private String soundPath = "/FIRST/blocks/sounds";
private File goldFile = new File("/sdcard" + soundPath + "/gold.wav");
private File silverFile = new File("/sdcard" + soundPath + "/silver.wav");
private final String soundPath = "/FIRST/blocks/sounds";
private final File goldFile = new File("/sdcard" + soundPath + "/gold.wav");
private final File silverFile = new File("/sdcard" + soundPath + "/silver.wav");

// Declare OpMode members.
private boolean isX = false; // Gamepad button state variables
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@
public class ConceptSoundsSKYSTONE extends LinearOpMode {

// List of available sound resources
String sounds[] = {"ss_alarm", "ss_bb8_down", "ss_bb8_up", "ss_darth_vader", "ss_fly_by",
String[] sounds = {"ss_alarm", "ss_bb8_down", "ss_bb8_up", "ss_darth_vader", "ss_fly_by",
"ss_mf_fail", "ss_laser", "ss_laser_burst", "ss_light_saber", "ss_light_saber_long", "ss_light_saber_short",
"ss_light_speed", "ss_mine", "ss_power_up", "ss_r2d2_up", "ss_roger_roger", "ss_siren", "ss_wookie" };
boolean soundPlaying = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ public class RobotAutoDriveByEncoder_Linear extends LinearOpMode {
private DcMotor leftDrive = null;
private DcMotor rightDrive = null;

private ElapsedTime runtime = new ElapsedTime();
private final ElapsedTime runtime = new ElapsedTime();

// Calculate the COUNTS_PER_INCH for your specific drive train.
// Go to your motor vendor website to determine your motor's COUNTS_PER_MOTOR_REV
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ public class RobotAutoDriveByTime_Linear extends LinearOpMode {
private DcMotor leftDrive = null;
private DcMotor rightDrive = null;

private ElapsedTime runtime = new ElapsedTime();
private final ElapsedTime runtime = new ElapsedTime();


static final double FORWARD_SPEED = 0.6;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -311,7 +311,7 @@ private void setManualExposure(int exposureMS, int gain) {
exposureControl.setMode(ExposureControl.Mode.Manual);
sleep(50);
}
exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS);
exposureControl.setExposure(exposureMS, TimeUnit.MILLISECONDS);
sleep(20);
GainControl gainControl = visionPortal.getCameraControl(GainControl.class);
gainControl.setGain(gain);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -286,7 +286,7 @@ private void setManualExposure(int exposureMS, int gain) {
exposureControl.setMode(ExposureControl.Mode.Manual);
sleep(50);
}
exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS);
exposureControl.setExposure(exposureMS, TimeUnit.MILLISECONDS);
sleep(20);
GainControl gainControl = visionPortal.getCameraControl(GainControl.class);
gainControl.setGain(gain);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ public class SensorKLNavxMicro extends LinearOpMode {
// Get a reference to a Modern Robotics GyroSensor object. We use several interfaces
// on this object to illustrate which interfaces support which functionality.
navxMicro = hardwareMap.get(NavxMicroNavigationSensor.class, "navx");
gyro = (IntegratingGyroscope)navxMicro;
gyro = navxMicro;
// If you're only interested int the IntegratingGyroscope interface, the following will suffice.
// gyro = hardwareMap.get(IntegratingGyroscope.class, "navx");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,10 @@ public class SensorMRColor extends LinearOpMode {
public void runOpMode() {

// hsvValues is an array that will hold the hue, saturation, and value information.
float hsvValues[] = {0F,0F,0F};
float[] hsvValues = {0F,0F,0F};

// values is a reference to the hsvValues array.
final float values[] = hsvValues;
final float[] values = hsvValues;

// get a reference to the RelativeLayout so we can change the background
// color of the Robot Controller app to match the hue detected by the RGB sensor.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ public void runOpMode() {
// Get a reference to a Modern Robotics gyro object. We use several interfaces
// on this object to illustrate which interfaces support which functionality.
modernRoboticsI2cGyro = hardwareMap.get(ModernRoboticsI2cGyro.class, "gyro");
gyro = (IntegratingGyroscope)modernRoboticsI2cGyro;
gyro = modernRoboticsI2cGyro;
// If you're only interested int the IntegratingGyroscope interface, the following will suffice.
// gyro = hardwareMap.get(IntegratingGyroscope.class, "gyro");
// A similar approach will work for the Gyroscope interface, if that's all you need.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -318,8 +318,8 @@ protected void onCreate(Bundle savedInstanceState) {
preferencesHelper.writeBooleanPrefIfDifferent(getString(R.string.pref_warn_about_incorrect_clocks), true);
}

entireScreenLayout = (LinearLayout) findViewById(R.id.entire_screen);
buttonMenu = (ImageButton) findViewById(R.id.menu_buttons);
entireScreenLayout = findViewById(R.id.entire_screen);
buttonMenu = findViewById(R.id.menu_buttons);
buttonMenu.setOnClickListener(new View.OnClickListener() {
@Override
public void onClick(View v) {
Expand All @@ -339,7 +339,7 @@ public boolean onMenuItemClick(MenuItem item) {

updateMonitorLayout(getResources().getConfiguration());

BlocksOpMode.setActivityAndWebView(this, (WebView) findViewById(R.id.webViewBlocksRuntime));
BlocksOpMode.setActivityAndWebView(this, findViewById(R.id.webViewBlocksRuntime));

ExternalLibraries.getInstance().onCreate();
onBotJavaHelper = new OnBotJavaHelperImpl();
Expand All @@ -365,13 +365,13 @@ public boolean onMenuItemClick(MenuItem item) {
cfgFileMgr.setActiveConfig(false, configFile);
}

textDeviceName = (TextView) findViewById(R.id.textDeviceName);
textNetworkConnectionStatus = (TextView) findViewById(R.id.textNetworkConnectionStatus);
textRobotStatus = (TextView) findViewById(R.id.textRobotStatus);
textOpMode = (TextView) findViewById(R.id.textOpMode);
textErrorMessage = (TextView) findViewById(R.id.textErrorMessage);
textGamepad[0] = (TextView) findViewById(R.id.textGamepad1);
textGamepad[1] = (TextView) findViewById(R.id.textGamepad2);
textDeviceName = findViewById(R.id.textDeviceName);
textNetworkConnectionStatus = findViewById(R.id.textNetworkConnectionStatus);
textRobotStatus = findViewById(R.id.textRobotStatus);
textOpMode = findViewById(R.id.textOpMode);
textErrorMessage = findViewById(R.id.textErrorMessage);
textGamepad[0] = findViewById(R.id.textGamepad1);
textGamepad[1] = findViewById(R.id.textGamepad2);
immersion = new ImmersiveMode(getWindow().getDecorView());
dimmer = new Dimmer(this);
dimmer.longBright();
Expand Down Expand Up @@ -501,7 +501,7 @@ protected void unbindFromService() {
protected void readNetworkType() {
// Control hubs are always running the access point model. Everything else, for the time
// being always runs the Wi-Fi Direct model.
if (Device.isRevControlHub() == true) {
if (Device.isRevControlHub()) {
networkType = NetworkType.RCWIRELESSAP;
} else {
networkType = NetworkType.fromString(preferencesHelper.readString(context.getString(R.string.pref_pairing_kind), NetworkType.globalDefaultAsString()));
Expand Down Expand Up @@ -541,11 +541,7 @@ private boolean isRobotRunning() {

RobotState robotState = robot.eventLoopManager.state;

if (robotState != RobotState.RUNNING) {
return false;
} else {
return true;
}
return robotState == RobotState.RUNNING;
}

@Override
Expand Down Expand Up @@ -629,7 +625,7 @@ public void onConfigurationChanged(Configuration newConfig) {
* based on the given configuration. Makes the children split the space.
*/
private void updateMonitorLayout(Configuration configuration) {
LinearLayout monitorContainer = (LinearLayout) findViewById(R.id.monitorContainer);
LinearLayout monitorContainer = findViewById(R.id.monitorContainer);
if (configuration.orientation == Configuration.ORIENTATION_LANDSCAPE) {
// When the phone is landscape, lay out the monitor views horizontally.
monitorContainer.setOrientation(LinearLayout.HORIZONTAL);
Expand Down Expand Up @@ -803,11 +799,7 @@ protected class SharedPreferencesListener implements SharedPreferences.OnSharedP
if (key.equals(context.getString(R.string.pref_app_theme))) {
ThemedActivity.restartForAppThemeChange(getTag(), getString(R.string.appThemeChangeRestartNotifyRC));
} else if (key.equals(context.getString(R.string.pref_wifi_automute))) {
if (preferencesHelper.readBoolean(context.getString(R.string.pref_wifi_automute), false)) {
initWifiMute(true);
} else {
initWifiMute(false);
}
initWifiMute(preferencesHelper.readBoolean(context.getString(R.string.pref_wifi_automute), false));
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@


public class PurplePixelComponent extends Component {
private TensorFlowDetection.PropPosition propPosition;
private final TensorFlowDetection.PropPosition propPosition;
public PurplePixelComponent(Robot robot, TensorFlowDetection.PropPosition propPosition) {
super(robot);
this.propPosition = propPosition;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ public class TrackingWheelLocalizer extends ThreeTrackingWheelLocalizer {
public Encoder leftEncoder, rightEncoder, frontEncoder;
public final double X_MULTIPLIER;// = 1.009485424; // Multiplier in the X direction
public final double Y_MULTIPLIER;// = 1.017838563; // Multiplier in the Y direction
private List<Integer> lastEncPositions, lastEncVels;
private final List<Integer> lastEncPositions;
private final List<Integer> lastEncVels;

public TrackingWheelLocalizer(HardwareMap hardwareMap, List<Integer> lastTrackingEncPositions, List<Integer> lastTrackingEncVels,
String leftEncoderName,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,20 +62,20 @@ public class TrajectoryDrive extends MecanumDrive {
public static double VY_WEIGHT = 1;
public static double OMEGA_WEIGHT = 1;

private TrajectorySequenceRunner trajectorySequenceRunner;
private final TrajectorySequenceRunner trajectorySequenceRunner;



private TrajectoryFollower follower;
private final TrajectoryFollower follower;

public DcMotorEx leftFront, leftRear, rightRear, rightFront;
private List<DcMotorEx> motors;
private final List<DcMotorEx> motors;

private IMU imu;
private VoltageSensor batteryVoltageSensor;
private final VoltageSensor batteryVoltageSensor;

private List<Integer> lastEncPositions = new ArrayList<>();
private List<Integer> lastEncVels = new ArrayList<>();
private final List<Integer> lastEncPositions = new ArrayList<>();
private final List<Integer> lastEncVels = new ArrayList<>();

private final TrajectoryAccelerationConstraint accelerationConstraint;
private final TrajectoryVelocityConstraint velocityConstraint;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@
public class ManualFeedforwardTuner extends LinearOpMode {
public static double DISTANCE = 72; // in

private FtcDashboard dashboard = FtcDashboard.getInstance();
private final FtcDashboard dashboard = FtcDashboard.getInstance();

//private PantheraDrive drive;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ public class MaxAngularVeloTuner extends LinearOpMode {
public static double RUNTIME = 4.0;

private ElapsedTime timer;
private double maxAngVelocity = 0.0;
private final double maxAngVelocity = 0.0;

@Override
public void runOpMode() throws InterruptedException {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public class MaxVelocityTuner extends LinearOpMode {
public static double RUNTIME = 2.0;

private ElapsedTime timer;
private double maxVelocity = 0.0;
private final double maxVelocity = 0.0;

private VoltageSensor batteryVoltageSensor;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,9 @@
public class LearningTeleOp extends LinearOpMode {





private DcMotor leftFrontMotor;
private DcMotor rightFrontMotor;
private DcMotor leftBackMotor;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
package org.firstinspires.ftc.teamcode.opmode;

import com.acmerobotics.dashboard.config.Config;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotor;

@Config
@TeleOp
public class LukeSpecifically extends LinearOpMode {


private DcMotor front_left;
private DcMotor front_right;
private DcMotor back_left;
private DcMotor back_right;
private CRServo servo_dog;
private CRServo grabber_dog;


@Override
public void runOpMode() throws InterruptedException {
waitForStart();

front_left = hardwareMap.get(DcMotor.class, "left_front_left_dw");
front_right = hardwareMap.get(DcMotor.class, "right_front");
back_left = hardwareMap.get(DcMotor.class, "left_back");
back_right = hardwareMap.get(DcMotor.class, "right_back_right_dw");
servo_dog = hardwareMap.get(CRServo.class, "servo");
grabber_dog = hardwareMap.get(CRServo.class, "Grabber");
while (opModeIsActive()) {

double y = -gamepad1.left_stick_y; // Remember, Y stick is reversed!
double x = gamepad1.left_stick_x;
double rx = gamepad1.right_stick_x;

front_left.setPower(-(y + x + rx));
back_left.setPower(-(y - x + rx));
front_right.setPower(y - x - rx);
back_right.setPower(y + x - rx);

if (gamepad1.right_bumper) {
servo_dog.setPower(1);
}//use if else and else statements before i kill you
if (gamepad1.left_bumper) {
servo_dog.setPower(0);
}
if (gamepad1.dpad_left) {
grabber_dog.setPower(-1);
}//make it stop
if (gamepad1.dpad_right) {
grabber_dog.setPower(1);
}
}


}

}
Loading

0 comments on commit b561675

Please sign in to comment.