Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tele op action #1

Open
wants to merge 3 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
4 changes: 2 additions & 2 deletions src/main/java/com/acmerobotics/robomatic/demo/DemoAuto.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;

@Autonomous(name="demoAuto")
//@Autonomous(name="demoAuto")
public class DemoAuto extends LinearOpMode {
@Override
public void runOpMode() {
DemoRobot robot = new DemoRobot(this);
DemoRobot robot = new DemoRobot(this, false);

DemoConfig config = (DemoConfig) new ConfigurationLoader(hardwareMap.appContext).getConfig();

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/acmerobotics/robomatic/demo/DemoRobot.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@ public class DemoRobot extends Robot {

public final DemoSubsystem subsystem;

public DemoRobot(LinearOpMode opmode) {
super(opmode);
public DemoRobot(LinearOpMode opmode, boolean inTeleOp) {
super(opmode, inTeleOp);

registerHub("hub0");

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/acmerobotics/robomatic/demo/DemoTeleOp.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,12 @@
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

@TeleOp(name="DemoTeleOp")
//@TeleOp(name="DemoTeleOp")
public class DemoTeleOp extends LinearOpMode {

@Override
public void runOpMode() {
DemoRobot robot = new DemoRobot(this);
DemoRobot robot = new DemoRobot(this, true);
StickyGamepad stickyGamepad1 = new StickyGamepad(gamepad1);

telemetry.addLine("init");
Expand Down
35 changes: 34 additions & 1 deletion src/main/java/com/acmerobotics/robomatic/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
import com.acmerobotics.robomatic.hardware.CachingSensor;
import com.acmerobotics.robomatic.hardware.CachingServo;
import com.acmerobotics.robomatic.hardware.LynxOptimizedI2cFactory;
import com.acmerobotics.robomatic.util.StickyGamepad;
import com.acmerobotics.robomatic.util.TeleOpActionImpl;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.hardware.bosch.BNO055IMUImpl;
import com.qualcomm.hardware.lynx.LynxEmbeddedIMU;
Expand Down Expand Up @@ -41,9 +43,15 @@ public abstract class Robot {

private HardwareMap map;
private LinearOpMode opmode;
private boolean inTeleOp;

private StickyGamepad stickyGamepad1;
private StickyGamepad stickyGamepad2;

private List<Subsystem> subsystems;

private List<TeleOpActionImpl> teleOpActions;

private Map<DcMotorController, LynxModule> motorControllers;
private Map<AnalogInputController, LynxModule> analogInputControllers;
private Map<DigitalChannelController, LynxModule> digitalChannelControllers;
Expand All @@ -59,9 +67,10 @@ public abstract class Robot {
private Map<String, Object> telemetry;
private List<String> telemetryLines;

public Robot (LinearOpMode opmode) {
public Robot (LinearOpMode opmode, boolean inTeleOp) {
this.map = opmode.hardwareMap;
this.opmode = opmode;
this.inTeleOp = inTeleOp;

motorControllers = new HashMap<>(2);
analogInputControllers = new HashMap<>(2);
Expand All @@ -78,6 +87,11 @@ public Robot (LinearOpMode opmode) {

subsystems = new ArrayList<>();

teleOpActions = new ArrayList<>();

stickyGamepad1 = new StickyGamepad(opmode.gamepad1);
stickyGamepad2 = new StickyGamepad(opmode.gamepad2);

}

public void addTelemetry (String caption, Object value) {
Expand Down Expand Up @@ -131,11 +145,22 @@ private void updateSubsystems () {
FtcDashboard.getInstance().sendTelemetryPacket(packet);
}

private void updateTeleOpAction(){
if (inTeleOp) {
for (TeleOpActionImpl teleOpAction : teleOpActions) {
teleOpAction.action(opmode.gamepad1, opmode.gamepad2, stickyGamepad1, stickyGamepad2);
stickyGamepad1.update();
stickyGamepad2.update();
}
}
}

public void update () {
updateBulkData();
updateCachingSensors();
updateSubsystems();
updateCachingHardwareDevices();
updateTeleOpAction();
}

public interface Target {
Expand Down Expand Up @@ -177,6 +202,10 @@ public DigitalChannel getDigitalChannel (String deviceName) {
return new BulkReadDigitalChannel(this, map.get(DigitalChannelImpl.class, deviceName));
}

public int getPhoneCameraId(){
return map.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", map.appContext.getPackageName());
}

protected void registerHub (String deviceName) {
LynxModule hub = map.get(LynxModule.class, deviceName);
hubs.add(hub);
Expand All @@ -193,6 +222,10 @@ public void registerCachingSensor (CachingSensor sensor) {
if (!cachingSensors.contains(sensor)) cachingSensors.add(sensor);
}

public void registerTeleOpAction(TeleOpActionImpl teleOpAction){
teleOpActions.add(teleOpAction);
}

private LynxGetBulkInputDataResponse getBulkResponse (DcMotorController controller) {
return bulkDataResponses.get(motorControllers.get(controller));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ public class StickyGamepad {
private boolean left_bumper_down, right_bumper_down;
private boolean left_stick_button_down, right_stick_button_down;

// makes it so a press and hold on the gamepad counts as a single press and doesn't get looped over
public StickyGamepad(Gamepad gamepad) {
this.gamepad = gamepad;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
package com.acmerobotics.robomatic.util;

import com.acmerobotics.robomatic.util.StickyGamepad;
import com.qualcomm.robotcore.hardware.Gamepad;

public interface TeleOpActionImpl {
Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Impl is short for Implementation, this is an interface

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

If you had some abstract interface and then a default implementation of that interface, you would call the implementation interfacenameImpl

void action(Gamepad gamepad1, Gamepad gamepad2, StickyGamepad stickyGamepad1, StickyGamepad stickyGamepad2);
}
Binary file added src/main/res/drawable-mdpi/field.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
6 changes: 6 additions & 0 deletions src/main/res/layout/activity_opmode_configuration.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,16 @@
<?xml version="1.0" encoding="utf-8"?>
<LinearLayout xmlns:android="http://schemas.android.com/apk/res/android"
xmlns:app="http://schemas.android.com/apk/res-auto"
xmlns:tools="http://schemas.android.com/tools"
android:orientation="vertical" android:layout_width="match_parent"
tools:context="com.acmerobotics.robomatic.config.OpModeConfigurationActivity"
android:id="@+id/opmode_config"
android:keepScreenOn="true"
android:layout_height="match_parent">

<ImageView
android:id="@+id/field"
android:layout_width="match_parent"
android:layout_height="413dp"
android:src="@drawable/field" />
</LinearLayout>