diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index 95d18d3..6ff791e 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -15,17 +15,19 @@ apply from: '../build.common.gradle' apply from: '../build.dependencies.gradle' apply plugin: 'org.jetbrains.kotlin.android' -apply plugin: 'org.team11260.fast-load-plugin' +//apply plugin: 'org.team11260.fast-load-plugin' buildscript { repositories { mavenCentral() - maven { url = 'https://www.matthewo.tech/maven/' } + + maven { + url = 'https://www.matthewo.tech/maven/' + } } dependencies { classpath 'org.team11260:fast-load-plugin:0.1.1' - } -} + }} repositories { maven { diff --git a/TeamCode/src/main/cpp/CMakeLists.txt b/TeamCode/src/main/cpp/CMakeLists.txt deleted file mode 100644 index b7ee074..0000000 --- a/TeamCode/src/main/cpp/CMakeLists.txt +++ /dev/null @@ -1,47 +0,0 @@ -cmake_minimum_required(VERSION 3.10) - -set(CMAKE_DEBUG_POSTFIX "") -set(BUILD_SHARED_LIBS ON) -set(BUILD_TESTS ON) -set(LIB_DIR ${CMAKE_SOURCE_DIR}/opencv/libs/${ANDROID_ABI}) - -# OpenCV -include_directories( - ${CMAKE_CURRENT_LIST_DIR}/main/libs/opencv/jni/include -) - -add_library(opencv-lib SHARED IMPORTED) -set_target_properties(opencv-lib - PROPERTIES IMPORTED_LOCATION - ${LIB_DIR}/libopencv_java4.so -) - - -# Add depthai-core - -add_subdirectory(depthai-core EXCLUDE_FROM_ALL) -project("GDOats") - -# add lib-usb -add_subdirectory(libusb) - -add_library( - GDOats - SHARED - main.cpp -) - - - -find_library( - log-lib - log -) - -target_link_libraries( - GDOats - opencv-lib - depthai::opencv - usb-1.0 - ${log-lib} -) \ No newline at end of file diff --git a/TeamCode/src/main/cpp/depthai-core b/TeamCode/src/main/cpp/depthai-core deleted file mode 160000 index bcd7a0e..0000000 --- a/TeamCode/src/main/cpp/depthai-core +++ /dev/null @@ -1 +0,0 @@ -Subproject commit bcd7a0e258a264f93ad249acf248bbc8ee617746 diff --git a/TeamCode/src/main/cpp/libusb b/TeamCode/src/main/cpp/libusb deleted file mode 160000 index 4588ef9..0000000 --- a/TeamCode/src/main/cpp/libusb +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 4588ef91e7b9c5fec71a88bbd94abc04040bcc5b diff --git a/TeamCode/src/main/cpp/main.cpp b/TeamCode/src/main/cpp/main.cpp deleted file mode 100644 index c919650..0000000 --- a/TeamCode/src/main/cpp/main.cpp +++ /dev/null @@ -1,45 +0,0 @@ -#include -#include -#include - -#include "depthai/depthai.hpp" -#include "opencv2/opencv.hpp" -#include -#include - -#define LOG_TAG "depthaiAndroid" -#define log(...) __android_log_print(ANDROID_LOG_INFO,LOG_TAG, __VA_ARGS__) - -std::shared_ptr device; -std::string AprilTagCode; - -extern "C" JNIEXPORT jstring JNICALL -Java_org_firstinspires_ftc_teamcode_Oak_CameraPreview_OakPrint(JNIEnv *env, jobject obj) { - std::string hello = AprilTagCode; - return env->NewStringUTF(hello.c_str()); -} - -extern "C" JNIEXPORT jstring JNICALL -Java_org_firstinspires_ftc_teamcode_Oak_CameraPreview_startDevice(JNIEnv *env, jobject) { - - auto r = libusb_set_option(nullptr, LIBUSB_OPTION_ANDROID_JNIENV, env); - log("libusb_set_option ANDROID_JAVAVM: %s", libusb_strerror(r)); - - std::string ret; - dai::Pipeline pipeline; - - try { - dai::BoardConfig config; - config.usb.pid = 0xf63b; - pipeline.setBoardConfig(config); - - auto deviceInfoVec = dai::Device::getAllAvailableDevices(); - dai::Device device(pipeline, deviceInfoVec[0], dai::UsbSpeed::SUPER); - - //device.startPipeline(pipeline); - } catch (const std::exception& e) { - log("Oak-1 Failed: %s", e.what()); - ret = e.what(); - } - return env->NewStringUTF(ret.c_str()); -} \ No newline at end of file diff --git a/TeamCode/src/main/cpp/opencv b/TeamCode/src/main/cpp/opencv deleted file mode 160000 index 6c57ce9..0000000 --- a/TeamCode/src/main/cpp/opencv +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 6c57ce9e09011763a973234f2e6d8acfe2984e1a diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/Diagnostic.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/Diagnostic.kt index b577c4f..e1fc5f9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/Diagnostic.kt +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmode/Diagnostic.kt @@ -35,10 +35,10 @@ class Diagnostic : LinearOpMode() { private fun testCircleDrive() { val traj = mecDrive.trajectoryBuilder(Pose2d()) - .splineTo(Vector2d(strafeLength, strafeLength), Math.toRadians(90.0)) - .splineTo(Vector2d(0.0, 2 * strafeLength), Math.toRadians(180.0)) - .splineTo(Vector2d(-strafeLength, strafeLength), Math.toRadians(270.0)) - .splineTo(Vector2d(0.0, 0.0), 0.0).build() + .splineTo(Vector2d(strafeLength, strafeLength), Math.toRadians(90.0)) + .splineTo(Vector2d(0.0, 2 * strafeLength), Math.toRadians(180.0)) + .splineTo(Vector2d(-strafeLength, strafeLength), Math.toRadians(270.0)) + .splineTo(Vector2d(0.0, 0.0), 0.0).build() this.telemetry.addLine("TEST: Circle Drive") mecDrive.followTrajectory(traj) @@ -49,16 +49,16 @@ class Diagnostic : LinearOpMode() { } private fun testSquareStrafe() { - val traj = mecDrive.trajectoryBuilder(mecDrive.poseEstimate) - .forward(strafeLength) - .strafeLeft(strafeLength) - .back(strafeLength) - .strafeRight(strafeLength) - .build() + val traj = mecDrive.trajectorySequenceBuilder(Pose2d(0.0,0.0,0.0)) + .forward(strafeLength) + .strafeLeft(strafeLength) + .back(strafeLength) + .strafeRight(strafeLength) + .build() this.telemetry.addLine("TEST: Square Strafe") this.telemetry.update() - mecDrive.followTrajectory(traj) + mecDrive.followTrajectorySequence(traj) while (mecDrive.isBusy) { sleep(20) }