FtcRobotController v7.2
This commit is contained in:
@ -20,6 +20,7 @@ android {
|
||||
sourceCompatibility JavaVersion.VERSION_1_7
|
||||
targetCompatibility JavaVersion.VERSION_1_7
|
||||
}
|
||||
namespace = 'com.qualcomm.ftcrobotcontroller'
|
||||
}
|
||||
|
||||
apply from: '../build.dependencies.gradle'
|
||||
|
@ -1,9 +1,8 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
|
||||
xmlns:tools="http://schemas.android.com/tools"
|
||||
package="com.qualcomm.ftcrobotcontroller"
|
||||
android:versionCode="44"
|
||||
android:versionName="7.1">
|
||||
android:versionCode="45"
|
||||
android:versionName="7.2">
|
||||
|
||||
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
|
||||
|
||||
|
@ -46,15 +46,17 @@ import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
* Both of these drives are illustrated at https://gm0.org/en/latest/docs/robot-design/drivetrains/holonomic.html
|
||||
* Note that a Mecanum drive must display an X roller-pattern when viewed from above.
|
||||
*
|
||||
* Also note that it is critical to set the correct rotation direction for each motor. See details below.
|
||||
*
|
||||
* Holonomic drives provide the ability for the robot to move in three axes (directions) simultaneously.
|
||||
* Each motion axis is controlled by one Joystick axis.
|
||||
*
|
||||
* 1) Axial: Driving forward and backwards Left-joystick Forward/Backwards
|
||||
* 1) Axial: Driving forward and backward Left-joystick Forward/Backward
|
||||
* 2) Lateral: Strafing right and left Left-joystick Right and Left
|
||||
* 3) Yaw: Rotating Clockwise and counter clockwise Right-joystick Right and Left
|
||||
*
|
||||
* This code is written assuming that the right-side motors need to be reversed for the robot to drive forward.
|
||||
* When you first test your robot, if it moves backwards when you push the left stick forward, then you must flip
|
||||
* When you first test your robot, if it moves backward when you push the left stick forward, then you must flip
|
||||
* the direction of all 4 motors (see code below).
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
@ -82,9 +84,16 @@ public class BasicOmniOpMode_Linear extends LinearOpMode {
|
||||
rightFrontDrive = hardwareMap.get(DcMotor.class, "right_front_drive");
|
||||
rightBackDrive = hardwareMap.get(DcMotor.class, "right_back_drive");
|
||||
|
||||
// ########################################################################################
|
||||
// !!! IMPORTANT Drive Information. Test your motor directions. !!!!!
|
||||
// ########################################################################################
|
||||
// Most robots need the motors on one side to be reversed to drive forward.
|
||||
// When you first test your robot, push the left joystick forward
|
||||
// and flip the direction ( FORWARD <-> REVERSE ) of any wheel that runs backwards
|
||||
// The motor reversals shown here are for a "direct drive" robot (the wheels turn the same direction as the motor shaft)
|
||||
// If your robot has additional gear reductions or uses a right-angled drive, it's important to ensure
|
||||
// that your motors are turning in the correct direction. So, start out with the reversals here, BUT
|
||||
// when you first test your robot, push the left joystick forward and observe the direction the wheels turn.
|
||||
// Reverse the direction (flip FORWARD <-> REVERSE ) of any wheel that runs backward
|
||||
// Keep testing until ALL the wheels move the robot forward when you push the left joystick forward.
|
||||
leftFrontDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
leftBackDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightFrontDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
@ -40,13 +40,13 @@ import com.qualcomm.robotcore.util.Range;
|
||||
* This file contains an example of an iterative (Non-Linear) "OpMode".
|
||||
* An OpMode is a 'program' that runs in either the autonomous or the teleop period of an FTC match.
|
||||
* The names of OpModes appear on the menu of the FTC Driver Station.
|
||||
* When an selection is made from the menu, the corresponding OpMode
|
||||
* When a selection is made from the menu, the corresponding OpMode
|
||||
* class is instantiated on the Robot Controller and executed.
|
||||
*
|
||||
* This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot
|
||||
* It includes all the skeletal structure that all iterative OpModes contain.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@ -72,10 +72,11 @@ public class BasicOpMode_Iterative extends OpMode
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// Most robots need the motor on one side to be reversed to drive forward
|
||||
// Reverse the motor that runs backwards when connected directly to the battery
|
||||
leftDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
rightDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
// Tell the driver that initialization is complete.
|
||||
telemetry.addData("Status", "Initialized");
|
||||
|
@ -40,13 +40,13 @@ import com.qualcomm.robotcore.util.Range;
|
||||
/**
|
||||
* This file contains an minimal example of a Linear "OpMode". An OpMode is a 'program' that runs in either
|
||||
* the autonomous or the teleop period of an FTC match. The names of OpModes appear on the menu
|
||||
* of the FTC Driver Station. When an selection is made from the menu, the corresponding OpMode
|
||||
* of the FTC Driver Station. When a selection is made from the menu, the corresponding OpMode
|
||||
* class is instantiated on the Robot Controller and executed.
|
||||
*
|
||||
* This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot
|
||||
* It includes all the skeletal structure that all linear OpModes contain.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@ -70,10 +70,11 @@ public class BasicOpMode_Linear extends LinearOpMode {
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// Most robots need the motor on one side to be reversed to drive forward
|
||||
// Reverse the motor that runs backwards when connected directly to the battery
|
||||
leftDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
rightDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
// Wait for the game to start (driver presses PLAY)
|
||||
waitForStart();
|
||||
|
@ -33,13 +33,11 @@ import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.CompassSensor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
/**
|
||||
* This file illustrates the concept of calibrating a MR Compass
|
||||
* It uses the common Pushbot hardware class to define the drive on the robot.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* This code assumes there is a compass configured with the name "compass"
|
||||
*
|
||||
* This code will put the compass into calibration mode, wait three seconds and then attempt
|
||||
@ -57,7 +55,8 @@ import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
public class ConceptCompassCalibration extends LinearOpMode {
|
||||
|
||||
/* Declare OpMode members. */
|
||||
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
|
||||
public DcMotor leftDrive = null;
|
||||
public DcMotor rightDrive = null;
|
||||
private ElapsedTime runtime = new ElapsedTime();
|
||||
CompassSensor compass;
|
||||
|
||||
@ -68,10 +67,15 @@ public class ConceptCompassCalibration extends LinearOpMode {
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
/* Initialize the drive system variables.
|
||||
* The init() method of the hardware class does all the work here
|
||||
*/
|
||||
robot.init(hardwareMap);
|
||||
// Initialize the drive system variables.
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
// get a reference to our Compass Sensor object.
|
||||
compass = hardwareMap.get(CompassSensor.class, "compass");
|
||||
@ -93,8 +97,8 @@ public class ConceptCompassCalibration extends LinearOpMode {
|
||||
// Start the robot rotating clockwise
|
||||
telemetry.addData("Compass", "Calibration mode. Turning the robot...");
|
||||
telemetry.update();
|
||||
robot.leftDrive.setPower(MOTOR_POWER);
|
||||
robot.rightDrive.setPower(-MOTOR_POWER);
|
||||
leftDrive.setPower(MOTOR_POWER);
|
||||
rightDrive.setPower(-MOTOR_POWER);
|
||||
|
||||
// run until time expires OR the driver presses STOP;
|
||||
runtime.reset();
|
||||
@ -103,8 +107,8 @@ public class ConceptCompassCalibration extends LinearOpMode {
|
||||
}
|
||||
|
||||
// Stop all motors and turn off claibration
|
||||
robot.leftDrive.setPower(0);
|
||||
robot.rightDrive.setPower(0);
|
||||
leftDrive.setPower(0);
|
||||
rightDrive.setPower(0);
|
||||
compass.setMode(CompassSensor.CompassMode.MEASUREMENT_MODE);
|
||||
telemetry.addData("Compass", "Returning to measurement mode");
|
||||
telemetry.update();
|
||||
|
@ -1,103 +0,0 @@
|
||||
/* Copyright (c) 2017 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.DeviceInterfaceModule;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
/**
|
||||
* This OpMode illustrates using the Device Interface Module as a signalling device.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* This code assumes a DIM name "dim".
|
||||
*
|
||||
* There are many examples where the robot might like to signal the driver, without requiring them
|
||||
* to look at the driver station. This might be something like a "ball in hopper" condition or a
|
||||
* "ready to shoot" condition.
|
||||
*
|
||||
* The DIM has two user settable indicator LEDs (one red one blue). These can be controlled
|
||||
* directly from your program.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
@TeleOp(name = "Concept: DIM As Indicator", group = "Concept")
|
||||
@Disabled
|
||||
public class ConceptDIMAsIndicator extends LinearOpMode {
|
||||
|
||||
static final int BLUE_LED = 0; // Blue LED channel on DIM
|
||||
static final int RED_LED = 1; // Red LED Channel on DIM
|
||||
|
||||
// Create timer to toggle LEDs
|
||||
private ElapsedTime runtime = new ElapsedTime();
|
||||
|
||||
// Define class members
|
||||
DeviceInterfaceModule dim;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
// Connect to motor (Assume standard left wheel)
|
||||
// Change the text in quotes to match any motor name on your robot.
|
||||
dim = hardwareMap.get(DeviceInterfaceModule.class, "dim");
|
||||
|
||||
// Toggle LEDs while Waiting for the start button
|
||||
telemetry.addData(">", "Press Play to test LEDs." );
|
||||
telemetry.update();
|
||||
|
||||
while (!isStarted()) {
|
||||
// Determine if we are on an odd or even second
|
||||
boolean even = (((int)(runtime.time()) & 0x01) == 0);
|
||||
dim.setLED(RED_LED, even); // Red for even
|
||||
dim.setLED(BLUE_LED, !even); // Blue for odd
|
||||
idle();
|
||||
}
|
||||
|
||||
// Running now
|
||||
telemetry.addData(">", "Press X for Blue, B for Red." );
|
||||
telemetry.update();
|
||||
|
||||
// Now just use red and blue buttons to set red and blue LEDs
|
||||
while(opModeIsActive()){
|
||||
dim.setLED(BLUE_LED, gamepad1.x);
|
||||
dim.setLED(RED_LED, gamepad1.b);
|
||||
idle();
|
||||
}
|
||||
|
||||
// Turn off LEDs;
|
||||
dim.setLED(BLUE_LED, false);
|
||||
dim.setLED(RED_LED, false);
|
||||
telemetry.addData(">", "Done");
|
||||
telemetry.update();
|
||||
}
|
||||
}
|
@ -1,223 +0,0 @@
|
||||
/* Copyright (c) 2017 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import com.qualcomm.hardware.modernrobotics.ModernRoboticsUsbDeviceInterfaceModule;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.DeviceInterfaceModule;
|
||||
import com.qualcomm.robotcore.hardware.I2cAddr;
|
||||
import com.qualcomm.robotcore.util.RobotLog;
|
||||
import com.qualcomm.robotcore.util.TypeConversion;
|
||||
|
||||
import java.util.concurrent.locks.Lock;
|
||||
|
||||
/**
|
||||
* An example of a linear op mode that shows how to change the I2C address.
|
||||
*/
|
||||
@TeleOp(name = "Concept: I2c Address Change", group = "Concept")
|
||||
@Disabled
|
||||
public class ConceptI2cAddressChange extends LinearOpMode {
|
||||
|
||||
public static final int ADDRESS_SET_NEW_I2C_ADDRESS = 0x70;
|
||||
// trigger bytes used to change I2C address on ModernRobotics sensors.
|
||||
public static final byte TRIGGER_BYTE_1 = 0x55;
|
||||
public static final byte TRIGGER_BYTE_2 = (byte) 0xaa;
|
||||
|
||||
// Expected bytes from the Modern Robotics IR Seeker V3 memory map
|
||||
public static final byte IR_SEEKER_V3_FIRMWARE_REV = 0x12;
|
||||
public static final byte IR_SEEKER_V3_SENSOR_ID = 0x49;
|
||||
public static final I2cAddr IR_SEEKER_V3_ORIGINAL_ADDRESS = I2cAddr.create8bit(0x38);
|
||||
|
||||
// Expected bytes from the Modern Robotics Color Sensor memory map
|
||||
public static final byte COLOR_SENSOR_FIRMWARE_REV = 0x10;
|
||||
public static final byte COLOR_SENSOR_SENSOR_ID = 0x43;
|
||||
public static final byte COLOR_SENSOR_ORIGINAL_ADDRESS = 0x3C;
|
||||
|
||||
public static final byte MANUFACTURER_CODE = 0x4d;
|
||||
// Currently, this is set to expect the bytes from the IR Seeker.
|
||||
// If you change these values so you're setting "FIRMWARE_REV" to
|
||||
// COLOR_SENSOR_FIRMWARE_REV, and "SENSOR_ID" to "COLOR_SENSOR_SENSOR_ID",
|
||||
// you'll be able to change the I2C address of the ModernRoboticsColorSensor.
|
||||
// If the bytes you're expecting are different than what this op mode finds,
|
||||
// a comparison will be printed out into the logfile.
|
||||
public static final byte FIRMWARE_REV = IR_SEEKER_V3_FIRMWARE_REV;
|
||||
public static final byte SENSOR_ID = IR_SEEKER_V3_SENSOR_ID;
|
||||
|
||||
// These byte values are common with most Modern Robotics sensors.
|
||||
public static final int READ_MODE = 0x80;
|
||||
public static final int ADDRESS_MEMORY_START = 0x0;
|
||||
public static final int TOTAL_MEMORY_LENGTH = 0x0c;
|
||||
public static final int BUFFER_CHANGE_ADDRESS_LENGTH = 0x03;
|
||||
|
||||
// The port where your sensor is connected.
|
||||
int port = 5;
|
||||
|
||||
byte[] readCache;
|
||||
Lock readLock;
|
||||
byte[] writeCache;
|
||||
Lock writeLock;
|
||||
|
||||
I2cAddr currentAddress = IR_SEEKER_V3_ORIGINAL_ADDRESS;
|
||||
// I2c addresses on Modern Robotics devices must be divisible by 2, and between 0x7e and 0x10
|
||||
// Different hardware may have different rules.
|
||||
// Be sure to read the requirements for the hardware you're using!
|
||||
// If you use an invalid address, you may make your device completely unusable.
|
||||
I2cAddr newAddress = I2cAddr.create8bit(0x42);
|
||||
|
||||
DeviceInterfaceModule dim;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
// set up the hardware devices we are going to use
|
||||
dim = hardwareMap.get(DeviceInterfaceModule.class, "dim");
|
||||
|
||||
readCache = dim.getI2cReadCache(port);
|
||||
readLock = dim.getI2cReadCacheLock(port);
|
||||
writeCache = dim.getI2cWriteCache(port);
|
||||
writeLock = dim.getI2cWriteCacheLock(port);
|
||||
|
||||
// I2c addresses on Modern Robotics devices must be divisible by 2, and between 0x7e and 0x10
|
||||
// Different hardware may have different rules.
|
||||
// Be sure to read the requirements for the hardware you're using!
|
||||
ModernRoboticsUsbDeviceInterfaceModule.throwIfModernRoboticsI2cAddressIsInvalid(newAddress);
|
||||
|
||||
// wait for the start button to be pressed
|
||||
waitForStart();
|
||||
|
||||
performAction("read", port, currentAddress, ADDRESS_MEMORY_START, TOTAL_MEMORY_LENGTH);
|
||||
|
||||
while(!dim.isI2cPortReady(port)) {
|
||||
telemetry.addData("I2cAddressChange", "waiting for the port to be ready...");
|
||||
telemetry.update();
|
||||
sleep(1000);
|
||||
}
|
||||
|
||||
// update the local cache
|
||||
dim.readI2cCacheFromController(port);
|
||||
|
||||
// make sure the first bytes are what we think they should be.
|
||||
int count = 0;
|
||||
int[] initialArray = {READ_MODE, currentAddress.get8Bit(), ADDRESS_MEMORY_START, TOTAL_MEMORY_LENGTH, FIRMWARE_REV, MANUFACTURER_CODE, SENSOR_ID};
|
||||
while (!foundExpectedBytes(initialArray, readLock, readCache)) {
|
||||
telemetry.addData("I2cAddressChange", "Confirming that we're reading the correct bytes...");
|
||||
telemetry.update();
|
||||
dim.readI2cCacheFromController(port);
|
||||
sleep(1000);
|
||||
count++;
|
||||
// if we go too long with failure, we probably are expecting the wrong bytes.
|
||||
if (count >= 10) {
|
||||
telemetry.addData("I2cAddressChange", String.format("Looping too long with no change, probably have the wrong address. Current address: 8bit=0x%02x", currentAddress.get8Bit()));
|
||||
hardwareMap.irSeekerSensor.get(String.format("Looping too long with no change, probably have the wrong address. Current address: 8bit=0x%02x", currentAddress.get8Bit()));
|
||||
telemetry.update();
|
||||
}
|
||||
}
|
||||
|
||||
// Enable writes to the correct segment of the memory map.
|
||||
performAction("write", port, currentAddress, ADDRESS_SET_NEW_I2C_ADDRESS, BUFFER_CHANGE_ADDRESS_LENGTH);
|
||||
|
||||
// Write out the trigger bytes, and the new desired address.
|
||||
writeNewAddress();
|
||||
dim.setI2cPortActionFlag(port);
|
||||
dim.writeI2cCacheToController(port);
|
||||
|
||||
telemetry.addData("I2cAddressChange", "Giving the hardware 60 seconds to make the change...");
|
||||
telemetry.update();
|
||||
|
||||
// Changing the I2C address takes some time.
|
||||
sleep(60000);
|
||||
|
||||
// Query the new address and see if we can get the bytes we expect.
|
||||
dim.enableI2cReadMode(port, newAddress, ADDRESS_MEMORY_START, TOTAL_MEMORY_LENGTH);
|
||||
dim.setI2cPortActionFlag(port);
|
||||
dim.writeI2cCacheToController(port);
|
||||
|
||||
int[] confirmArray = {READ_MODE, newAddress.get8Bit(), ADDRESS_MEMORY_START, TOTAL_MEMORY_LENGTH, FIRMWARE_REV, MANUFACTURER_CODE, SENSOR_ID};
|
||||
while (!foundExpectedBytes(confirmArray, readLock, readCache)) {
|
||||
telemetry.addData("I2cAddressChange", "Have not confirmed the changes yet...");
|
||||
telemetry.update();
|
||||
dim.readI2cCacheFromController(port);
|
||||
sleep(1000);
|
||||
}
|
||||
|
||||
telemetry.addData("I2cAddressChange", "Successfully changed the I2C address. New address: 8bit=0x%02x", newAddress.get8Bit());
|
||||
telemetry.update();
|
||||
RobotLog.i("Successfully changed the I2C address." + String.format("New address: 8bit=0x%02x", newAddress.get8Bit()));
|
||||
|
||||
/**** IMPORTANT NOTE ******/
|
||||
// You need to add a line like this at the top of your op mode
|
||||
// to update the I2cAddress in the driver.
|
||||
//irSeeker.setI2cAddress(newAddress);
|
||||
/***************************/
|
||||
|
||||
}
|
||||
|
||||
private boolean foundExpectedBytes(int[] byteArray, Lock lock, byte[] cache) {
|
||||
try {
|
||||
lock.lock();
|
||||
boolean allMatch = true;
|
||||
StringBuilder s = new StringBuilder(300 * 4);
|
||||
String mismatch = "";
|
||||
for (int i = 0; i < byteArray.length; i++) {
|
||||
s.append(String.format("expected: %02x, got: %02x \n", TypeConversion.unsignedByteToInt( (byte) byteArray[i]), cache[i]));
|
||||
if (TypeConversion.unsignedByteToInt(cache[i]) != TypeConversion.unsignedByteToInt( (byte) byteArray[i])) {
|
||||
mismatch = String.format("i: %d, byteArray[i]: %02x, cache[i]: %02x", i, byteArray[i], cache[i]);
|
||||
allMatch = false;
|
||||
}
|
||||
}
|
||||
RobotLog.e(s.toString() + "\n allMatch: " + allMatch + ", mismatch: " + mismatch);
|
||||
return allMatch;
|
||||
} finally {
|
||||
lock.unlock();
|
||||
}
|
||||
}
|
||||
|
||||
private void performAction(String actionName, int port, I2cAddr i2cAddress, int memAddress, int memLength) {
|
||||
if (actionName.equalsIgnoreCase("read")) dim.enableI2cReadMode(port, i2cAddress, memAddress, memLength);
|
||||
if (actionName.equalsIgnoreCase("write")) dim.enableI2cWriteMode(port, i2cAddress, memAddress, memLength);
|
||||
|
||||
dim.setI2cPortActionFlag(port);
|
||||
dim.writeI2cCacheToController(port);
|
||||
dim.readI2cCacheFromController(port);
|
||||
}
|
||||
|
||||
private void writeNewAddress() {
|
||||
try {
|
||||
writeLock.lock();
|
||||
writeCache[4] = (byte) newAddress.get8Bit();
|
||||
writeCache[5] = TRIGGER_BYTE_1;
|
||||
writeCache[6] = TRIGGER_BYTE_2;
|
||||
} finally {
|
||||
writeLock.unlock();
|
||||
}
|
||||
}
|
||||
}
|
@ -38,7 +38,7 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
* This OpMode ramps a single motor speed up and down repeatedly until Stop is pressed.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* This code assumes a DC motor configured with the name "left_drive" as is found on a pushbot.
|
||||
* This code assumes a DC motor configured with the name "left_drive" as is found on a Robot.
|
||||
*
|
||||
* INCREMENT sets how much to increase/decrease the power each cycle
|
||||
* CYCLE_MS sets the update period.
|
||||
|
@ -44,8 +44,8 @@ import com.qualcomm.robotcore.util.Range;
|
||||
* robot configuration, use the drop down list under 'Servos' to select 'REV SPARKmini Controller'
|
||||
* and name them 'left_drive' and 'right_drive'.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@TeleOp(name="REV SPARKmini Simple Drive Example", group="Concept")
|
||||
@ -69,7 +69,7 @@ public class ConceptRevSPARKMini extends LinearOpMode {
|
||||
rightDrive = hardwareMap.get(DcMotorSimple.class, "right_drive");
|
||||
|
||||
// Most robots need the motor on one side to be reversed to drive forward
|
||||
// Reverse the motor that runs backwards when connected directly to the battery
|
||||
// Reverse the motor that runs backward when connected directly to the battery
|
||||
leftDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||
rightDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
|
@ -35,12 +35,12 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
/**
|
||||
* This OpMode scans a single servo back and forwards until Stop is pressed.
|
||||
* This OpMode scans a single servo back and forward until Stop is pressed.
|
||||
* The code is structured as a LinearOpMode
|
||||
* INCREMENT sets how much to increase/decrease the servo position each cycle
|
||||
* CYCLE_MS sets the update period.
|
||||
*
|
||||
* This code assumes a Servo configured with the name "left_hand" as is found on a pushbot.
|
||||
* This code assumes a Servo configured with the name "left_hand" as is found on a Robot.
|
||||
*
|
||||
* NOTE: When any servo position is set, ALL attached servos are activated, so ensure that any other
|
||||
* connected servos are able to move freely before running this test.
|
||||
@ -66,7 +66,7 @@ public class ConceptScanServo extends LinearOpMode {
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
// Connect to servo (Assume PushBot Left Hand)
|
||||
// Connect to servo (Assume Robot Left Hand)
|
||||
// Change the text in quotes to match any servo name on your robot.
|
||||
servo = hardwareMap.get(Servo.class, "left_hand");
|
||||
|
||||
|
@ -43,7 +43,7 @@ import java.io.File;
|
||||
*
|
||||
* If you are using OnBotJava, please see the ConceptSoundsOnBotJava sample
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*
|
||||
* Operation:
|
||||
|
@ -41,8 +41,8 @@ import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
* It does this by creating a simple "chooser" controlled by the gamepad Up Down buttons.
|
||||
* This code also prevents sounds from stacking up by setting a "playing" flag, which is cleared when the sound finishes playing.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
|
||||
*
|
||||
* Operation:
|
||||
* Use the DPAD to change the selected sound, and the Right Bumper to play it.
|
||||
|
@ -44,7 +44,7 @@ import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
|
||||
* determine the position of the Freight Frenzy game elements.
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
|
||||
*
|
||||
* IMPORTANT: In order to use this OpMode, you need to obtain your own Vuforia license key as
|
||||
* is explained below.
|
||||
|
@ -59,7 +59,7 @@ import org.firstinspires.ftc.robotcore.external.navigation.VuforiaTrackables;
|
||||
* see ftc_app/doc/tutorial/FTC_FieldCoordinateSystemDefinition.pdf
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
|
||||
*
|
||||
* IMPORTANT: In order to use this OpMode, you need to obtain your own Vuforia license key as
|
||||
* is explained in {@link ConceptVuforiaNavigation}.
|
||||
|
@ -60,7 +60,7 @@ import org.firstinspires.ftc.robotcore.external.navigation.VuforiaTrackables;
|
||||
* see ftc_app/doc/tutorial/FTC_FieldCoordinateSystemDefinition.pdf
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
|
||||
*
|
||||
* IMPORTANT: In order to use this OpMode, you need to obtain your own Vuforia license key as
|
||||
* is explained in {@link ConceptVuforiaNavigationWebcam}.
|
||||
|
@ -112,9 +112,10 @@ public class ConceptVuforiaDriveToTargetWebcam extends LinearOpMode
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
|
||||
leftDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
rightDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
// When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
telemetry.addData(">", "Press Play to start");
|
||||
telemetry.update();
|
||||
|
@ -67,7 +67,7 @@ import static org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocaliz
|
||||
* To learn more about the FTC field coordinate model, see FTC_FieldCoordinateSystemDefinition.pdf in this folder
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
|
||||
*
|
||||
* IMPORTANT: In order to use this OpMode, you need to obtain your own Vuforia license key as
|
||||
* is explained below.
|
||||
|
@ -69,7 +69,7 @@ import static org.firstinspires.ftc.robotcore.external.navigation.AxesReference.
|
||||
* To learn more about the FTC field coordinate model, see FTC_FieldCoordinateSystemDefinition.pdf in this folder
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
|
||||
*
|
||||
* IMPORTANT: In order to use this OpMode, you need to obtain your own Vuforia license key as
|
||||
* is explained below.
|
||||
|
@ -1,310 +0,0 @@
|
||||
/* Copyright (c) 2020 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import android.graphics.Bitmap;
|
||||
import android.graphics.ImageFormat;
|
||||
import android.os.Handler;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.util.RobotLog;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.ClassFactory;
|
||||
import org.firstinspires.ftc.robotcore.external.android.util.Size;
|
||||
import org.firstinspires.ftc.robotcore.external.function.Consumer;
|
||||
import org.firstinspires.ftc.robotcore.external.function.Continuation;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.Camera;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.CameraCaptureRequest;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.CameraCaptureSequenceId;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.CameraCaptureSession;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.CameraCharacteristics;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.CameraException;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.CameraFrame;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.CameraManager;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||
import org.firstinspires.ftc.robotcore.internal.collections.EvictingBlockingQueue;
|
||||
import org.firstinspires.ftc.robotcore.internal.network.CallbackLooper;
|
||||
import org.firstinspires.ftc.robotcore.internal.system.AppUtil;
|
||||
import org.firstinspires.ftc.robotcore.internal.system.ContinuationSynchronizer;
|
||||
import org.firstinspires.ftc.robotcore.internal.system.Deadline;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.FileOutputStream;
|
||||
import java.io.IOException;
|
||||
import java.util.Locale;
|
||||
import java.util.concurrent.ArrayBlockingQueue;
|
||||
import java.util.concurrent.TimeUnit;
|
||||
|
||||
/**
|
||||
* This OpMode illustrates how to open a webcam and retrieve images from it. It requires a configuration
|
||||
* containing a webcam with the default name ("Webcam 1"). When the opmode runs, pressing the 'A' button
|
||||
* will cause a frame from the camera to be written to a file on the device, which can then be retrieved
|
||||
* by various means (e.g.: Device File Explorer in Android Studio; plugging the device into a PC and
|
||||
* using Media Transfer; ADB; etc)
|
||||
*/
|
||||
@TeleOp(name="Concept: Webcam", group ="Concept")
|
||||
@Disabled
|
||||
public class ConceptWebcam extends LinearOpMode {
|
||||
|
||||
//----------------------------------------------------------------------------------------------
|
||||
// State
|
||||
//----------------------------------------------------------------------------------------------
|
||||
|
||||
private static final String TAG = "Webcam Sample";
|
||||
|
||||
/** How long we are to wait to be granted permission to use the camera before giving up. Here,
|
||||
* we wait indefinitely */
|
||||
private static final int secondsPermissionTimeout = Integer.MAX_VALUE;
|
||||
|
||||
/** State regarding our interaction with the camera */
|
||||
private CameraManager cameraManager;
|
||||
private WebcamName cameraName;
|
||||
private Camera camera;
|
||||
private CameraCaptureSession cameraCaptureSession;
|
||||
|
||||
/** The queue into which all frames from the camera are placed as they become available.
|
||||
* Frames which are not processed by the OpMode are automatically discarded. */
|
||||
private EvictingBlockingQueue<Bitmap> frameQueue;
|
||||
|
||||
/** State regarding where and how to save frames when the 'A' button is pressed. */
|
||||
private int captureCounter = 0;
|
||||
private File captureDirectory = AppUtil.ROBOT_DATA_DIR;
|
||||
|
||||
/** A utility object that indicates where the asynchronous callbacks from the camera
|
||||
* infrastructure are to run. In this OpMode, that's all hidden from you (but see {@link #startCamera}
|
||||
* if you're curious): no knowledge of multi-threading is needed here. */
|
||||
private Handler callbackHandler;
|
||||
|
||||
//----------------------------------------------------------------------------------------------
|
||||
// Main OpMode entry
|
||||
//----------------------------------------------------------------------------------------------
|
||||
|
||||
@Override public void runOpMode() {
|
||||
|
||||
callbackHandler = CallbackLooper.getDefault().getHandler();
|
||||
|
||||
cameraManager = ClassFactory.getInstance().getCameraManager();
|
||||
cameraName = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||
|
||||
initializeFrameQueue(2);
|
||||
AppUtil.getInstance().ensureDirectoryExists(captureDirectory);
|
||||
|
||||
try {
|
||||
openCamera();
|
||||
if (camera == null) return;
|
||||
|
||||
startCamera();
|
||||
if (cameraCaptureSession == null) return;
|
||||
|
||||
telemetry.addData(">", "Press Play to start");
|
||||
telemetry.update();
|
||||
waitForStart();
|
||||
telemetry.clear();
|
||||
telemetry.addData(">", "Started...Press 'A' to capture frame");
|
||||
|
||||
boolean buttonPressSeen = false;
|
||||
boolean captureWhenAvailable = false;
|
||||
while (opModeIsActive()) {
|
||||
|
||||
boolean buttonIsPressed = gamepad1.a;
|
||||
if (buttonIsPressed && !buttonPressSeen) {
|
||||
captureWhenAvailable = true;
|
||||
}
|
||||
buttonPressSeen = buttonIsPressed;
|
||||
|
||||
if (captureWhenAvailable) {
|
||||
Bitmap bmp = frameQueue.poll();
|
||||
if (bmp != null) {
|
||||
captureWhenAvailable = false;
|
||||
onNewFrame(bmp);
|
||||
}
|
||||
}
|
||||
|
||||
telemetry.update();
|
||||
}
|
||||
} finally {
|
||||
closeCamera();
|
||||
}
|
||||
}
|
||||
|
||||
/** Do something with the frame */
|
||||
private void onNewFrame(Bitmap frame) {
|
||||
saveBitmap(frame);
|
||||
frame.recycle(); // not strictly necessary, but helpful
|
||||
}
|
||||
|
||||
//----------------------------------------------------------------------------------------------
|
||||
// Camera operations
|
||||
//----------------------------------------------------------------------------------------------
|
||||
|
||||
private void initializeFrameQueue(int capacity) {
|
||||
/** The frame queue will automatically throw away bitmap frames if they are not processed
|
||||
* quickly by the OpMode. This avoids a buildup of frames in memory */
|
||||
frameQueue = new EvictingBlockingQueue<Bitmap>(new ArrayBlockingQueue<Bitmap>(capacity));
|
||||
frameQueue.setEvictAction(new Consumer<Bitmap>() {
|
||||
@Override public void accept(Bitmap frame) {
|
||||
// RobotLog.ii(TAG, "frame recycled w/o processing");
|
||||
frame.recycle(); // not strictly necessary, but helpful
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
private void openCamera() {
|
||||
if (camera != null) return; // be idempotent
|
||||
|
||||
Deadline deadline = new Deadline(secondsPermissionTimeout, TimeUnit.SECONDS);
|
||||
camera = cameraManager.requestPermissionAndOpenCamera(deadline, cameraName, null);
|
||||
if (camera == null) {
|
||||
error("camera not found or permission to use not granted: %s", cameraName);
|
||||
}
|
||||
}
|
||||
|
||||
private void startCamera() {
|
||||
if (cameraCaptureSession != null) return; // be idempotent
|
||||
|
||||
/** YUY2 is supported by all Webcams, per the USB Webcam standard: See "USB Device Class Definition
|
||||
* for Video Devices: Uncompressed Payload, Table 2-1". Further, often this is the *only*
|
||||
* image format supported by a camera */
|
||||
final int imageFormat = ImageFormat.YUY2;
|
||||
|
||||
/** Verify that the image is supported, and fetch size and desired frame rate if so */
|
||||
CameraCharacteristics cameraCharacteristics = cameraName.getCameraCharacteristics();
|
||||
if (!contains(cameraCharacteristics.getAndroidFormats(), imageFormat)) {
|
||||
error("image format not supported");
|
||||
return;
|
||||
}
|
||||
final Size size = cameraCharacteristics.getDefaultSize(imageFormat);
|
||||
final int fps = cameraCharacteristics.getMaxFramesPerSecond(imageFormat, size);
|
||||
|
||||
/** Some of the logic below runs asynchronously on other threads. Use of the synchronizer
|
||||
* here allows us to wait in this method until all that asynchrony completes before returning. */
|
||||
final ContinuationSynchronizer<CameraCaptureSession> synchronizer = new ContinuationSynchronizer<>();
|
||||
try {
|
||||
/** Create a session in which requests to capture frames can be made */
|
||||
camera.createCaptureSession(Continuation.create(callbackHandler, new CameraCaptureSession.StateCallbackDefault() {
|
||||
@Override public void onConfigured(@NonNull CameraCaptureSession session) {
|
||||
try {
|
||||
/** The session is ready to go. Start requesting frames */
|
||||
final CameraCaptureRequest captureRequest = camera.createCaptureRequest(imageFormat, size, fps);
|
||||
session.startCapture(captureRequest,
|
||||
new CameraCaptureSession.CaptureCallback() {
|
||||
@Override public void onNewFrame(@NonNull CameraCaptureSession session, @NonNull CameraCaptureRequest request, @NonNull CameraFrame cameraFrame) {
|
||||
/** A new frame is available. The frame data has <em>not</em> been copied for us, and we can only access it
|
||||
* for the duration of the callback. So we copy here manually. */
|
||||
Bitmap bmp = captureRequest.createEmptyBitmap();
|
||||
cameraFrame.copyToBitmap(bmp);
|
||||
frameQueue.offer(bmp);
|
||||
}
|
||||
},
|
||||
Continuation.create(callbackHandler, new CameraCaptureSession.StatusCallback() {
|
||||
@Override public void onCaptureSequenceCompleted(@NonNull CameraCaptureSession session, CameraCaptureSequenceId cameraCaptureSequenceId, long lastFrameNumber) {
|
||||
RobotLog.ii(TAG, "capture sequence %s reports completed: lastFrame=%d", cameraCaptureSequenceId, lastFrameNumber);
|
||||
}
|
||||
})
|
||||
);
|
||||
synchronizer.finish(session);
|
||||
} catch (CameraException|RuntimeException e) {
|
||||
RobotLog.ee(TAG, e, "exception starting capture");
|
||||
error("exception starting capture");
|
||||
session.close();
|
||||
synchronizer.finish(null);
|
||||
}
|
||||
}
|
||||
}));
|
||||
} catch (CameraException|RuntimeException e) {
|
||||
RobotLog.ee(TAG, e, "exception starting camera");
|
||||
error("exception starting camera");
|
||||
synchronizer.finish(null);
|
||||
}
|
||||
|
||||
/** Wait for all the asynchrony to complete */
|
||||
try {
|
||||
synchronizer.await();
|
||||
} catch (InterruptedException e) {
|
||||
Thread.currentThread().interrupt();
|
||||
}
|
||||
|
||||
/** Retrieve the created session. This will be null on error. */
|
||||
cameraCaptureSession = synchronizer.getValue();
|
||||
}
|
||||
|
||||
private void stopCamera() {
|
||||
if (cameraCaptureSession != null) {
|
||||
cameraCaptureSession.stopCapture();
|
||||
cameraCaptureSession.close();
|
||||
cameraCaptureSession = null;
|
||||
}
|
||||
}
|
||||
|
||||
private void closeCamera() {
|
||||
stopCamera();
|
||||
if (camera != null) {
|
||||
camera.close();
|
||||
camera = null;
|
||||
}
|
||||
}
|
||||
|
||||
//----------------------------------------------------------------------------------------------
|
||||
// Utilities
|
||||
//----------------------------------------------------------------------------------------------
|
||||
|
||||
private void error(String msg) {
|
||||
telemetry.log().add(msg);
|
||||
telemetry.update();
|
||||
}
|
||||
private void error(String format, Object...args) {
|
||||
telemetry.log().add(format, args);
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
private boolean contains(int[] array, int value) {
|
||||
for (int i : array) {
|
||||
if (i == value) return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
private void saveBitmap(Bitmap bitmap) {
|
||||
File file = new File(captureDirectory, String.format(Locale.getDefault(), "webcam-frame-%d.jpg", captureCounter++));
|
||||
try {
|
||||
try (FileOutputStream outputStream = new FileOutputStream(file)) {
|
||||
bitmap.compress(Bitmap.CompressFormat.JPEG, 100, outputStream);
|
||||
telemetry.log().add("captured %s", file.getName());
|
||||
}
|
||||
} catch (IOException e) {
|
||||
RobotLog.ee(TAG, e, "exception in saveBitmap()");
|
||||
error("exception saving %s", file.getName());
|
||||
}
|
||||
}
|
||||
}
|
@ -1,105 +0,0 @@
|
||||
/* Copyright (c) 2017 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
/**
|
||||
* This is NOT an opmode.
|
||||
*
|
||||
* This class can be used to define all the specific hardware for a single robot.
|
||||
* In this case that robot is a Pushbot.
|
||||
* See PushbotTeleopTank_Iterative and others classes starting with "Pushbot" for usage examples.
|
||||
*
|
||||
* This hardware class assumes the following device names have been configured on the robot:
|
||||
* Note: All names are lower case and some have single spaces between words.
|
||||
*
|
||||
* Motor channel: Left drive motor: "left_drive"
|
||||
* Motor channel: Right drive motor: "right_drive"
|
||||
* Motor channel: Manipulator drive motor: "left_arm"
|
||||
* Servo channel: Servo to open left claw: "left_hand"
|
||||
* Servo channel: Servo to open right claw: "right_hand"
|
||||
*/
|
||||
public class HardwarePushbot
|
||||
{
|
||||
/* Public OpMode members. */
|
||||
public DcMotor leftDrive = null;
|
||||
public DcMotor rightDrive = null;
|
||||
public DcMotor leftArm = null;
|
||||
public Servo leftClaw = null;
|
||||
public Servo rightClaw = null;
|
||||
|
||||
public static final double MID_SERVO = 0.5 ;
|
||||
public static final double ARM_UP_POWER = 0.45 ;
|
||||
public static final double ARM_DOWN_POWER = -0.45 ;
|
||||
|
||||
/* local OpMode members. */
|
||||
HardwareMap hwMap = null;
|
||||
private ElapsedTime period = new ElapsedTime();
|
||||
|
||||
/* Constructor */
|
||||
public HardwarePushbot(){
|
||||
|
||||
}
|
||||
|
||||
/* Initialize standard Hardware interfaces */
|
||||
public void init(HardwareMap ahwMap) {
|
||||
// Save reference to Hardware map
|
||||
hwMap = ahwMap;
|
||||
|
||||
// Define and Initialize Motors
|
||||
leftDrive = hwMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hwMap.get(DcMotor.class, "right_drive");
|
||||
leftArm = hwMap.get(DcMotor.class, "left_arm");
|
||||
leftDrive.setDirection(DcMotor.Direction.FORWARD); // Set to REVERSE if using AndyMark motors
|
||||
rightDrive.setDirection(DcMotor.Direction.REVERSE);// Set to FORWARD if using AndyMark motors
|
||||
|
||||
// Set all motors to zero power
|
||||
leftDrive.setPower(0);
|
||||
rightDrive.setPower(0);
|
||||
leftArm.setPower(0);
|
||||
|
||||
// Set all motors to run without encoders.
|
||||
// May want to use RUN_USING_ENCODERS if encoders are installed.
|
||||
leftDrive.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
leftArm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
|
||||
// Define and initialize ALL installed servos.
|
||||
leftClaw = hwMap.get(Servo.class, "left_hand");
|
||||
rightClaw = hwMap.get(Servo.class, "right_hand");
|
||||
leftClaw.setPosition(MID_SERVO);
|
||||
rightClaw.setPosition(MID_SERVO);
|
||||
}
|
||||
}
|
||||
|
@ -1,118 +0,0 @@
|
||||
/* Copyright (c) 2017 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.hardware.LightSensor;
|
||||
|
||||
/**
|
||||
* This file illustrates the concept of driving up to a line and then stopping.
|
||||
* It uses the common Pushbot hardware class to define the drive on the robot.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* The code shows using two different light sensors:
|
||||
* The Primary sensor shown in this code is a legacy NXT Light sensor (called "sensor_light")
|
||||
* Alternative "commented out" code uses a MR Optical Distance Sensor (called "sensor_ods")
|
||||
* instead of the LEGO sensor. Chose to use one sensor or the other.
|
||||
*
|
||||
* Setting the correct WHITE_THRESHOLD value is key to stopping correctly.
|
||||
* This should be set half way between the light and dark values.
|
||||
* These values can be read on the screen once the OpMode has been INIT, but before it is STARTED.
|
||||
* Move the senso on asnd off the white line and not the min and max readings.
|
||||
* Edit this code to make WHITE_THRESHOLD half way between the min and max.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@Autonomous(name="Pushbot: Auto Drive To Line", group="Pushbot")
|
||||
@Disabled
|
||||
public class PushbotAutoDriveToLine_Linear extends LinearOpMode {
|
||||
|
||||
/* Declare OpMode members. */
|
||||
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
|
||||
LightSensor lightSensor; // Primary LEGO Light sensor,
|
||||
// OpticalDistanceSensor lightSensor; // Alternative MR ODS sensor
|
||||
|
||||
static final double WHITE_THRESHOLD = 0.2; // spans between 0.1 - 0.5 from dark to light
|
||||
static final double APPROACH_SPEED = 0.5;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
/* Initialize the drive system variables.
|
||||
* The init() method of the hardware class does all the work here
|
||||
*/
|
||||
robot.init(hardwareMap);
|
||||
|
||||
// If there are encoders connected, switch to RUN_USING_ENCODER mode for greater accuracy
|
||||
// robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
// robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// get a reference to our Light Sensor object.
|
||||
lightSensor = hardwareMap.lightSensor.get("sensor_light"); // Primary LEGO Light Sensor
|
||||
// lightSensor = hardwareMap.opticalDistanceSensor.get("sensor_ods"); // Alternative MR ODS sensor.
|
||||
|
||||
// turn on LED of light sensor.
|
||||
lightSensor.enableLed(true);
|
||||
|
||||
// Send telemetry message to signify robot waiting;
|
||||
telemetry.addData("Status", "Ready to run"); //
|
||||
telemetry.update();
|
||||
|
||||
// Wait for the game to start (driver presses PLAY)
|
||||
// Abort this loop is started or stopped.
|
||||
while (!(isStarted() || isStopRequested())) {
|
||||
|
||||
// Display the light level while we are waiting to start
|
||||
telemetry.addData("Light Level", lightSensor.getLightDetected());
|
||||
telemetry.update();
|
||||
idle();
|
||||
}
|
||||
|
||||
// Start the robot moving forward, and then begin looking for a white line.
|
||||
robot.leftDrive.setPower(APPROACH_SPEED);
|
||||
robot.rightDrive.setPower(APPROACH_SPEED);
|
||||
|
||||
// run until the white line is seen OR the driver presses STOP;
|
||||
while (opModeIsActive() && (lightSensor.getLightDetected() < WHITE_THRESHOLD)) {
|
||||
|
||||
// Display the light level while we are looking for the line
|
||||
telemetry.addData("Light Level", lightSensor.getLightDetected());
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Stop all motors
|
||||
robot.leftDrive.setPower(0);
|
||||
robot.rightDrive.setPower(0);
|
||||
}
|
||||
}
|
@ -33,45 +33,53 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
/**
|
||||
* This file illustrates the concept of driving a path based on encoder counts.
|
||||
* It uses the common Pushbot hardware class to define the drive on the robot.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* The code REQUIRES that you DO have encoders on the wheels,
|
||||
* otherwise you would use: PushbotAutoDriveByTime;
|
||||
* otherwise you would use: RobotAutoDriveByTime;
|
||||
*
|
||||
* This code ALSO requires that the drive Motors have been configured such that a positive
|
||||
* power command moves them forwards, and causes the encoders to count UP.
|
||||
* power command moves them forward, and causes the encoders to count UP.
|
||||
*
|
||||
* The desired path in this example is:
|
||||
* - Drive forward for 48 inches
|
||||
* - Spin right for 12 Inches
|
||||
* - Drive Backwards for 24 inches
|
||||
* - Drive Backward for 24 inches
|
||||
* - Stop and close the claw.
|
||||
*
|
||||
* The code is written using a method called: encoderDrive(speed, leftInches, rightInches, timeoutS)
|
||||
* that performs the actual movement.
|
||||
* This methods assumes that each movement is relative to the last stopping place.
|
||||
* This method assumes that each movement is relative to the last stopping place.
|
||||
* There are other ways to perform encoder based moves, but this method is probably the simplest.
|
||||
* This code uses the RUN_TO_POSITION mode to enable the Motor controllers to generate the run profile
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@Autonomous(name="Pushbot: Auto Drive By Encoder", group="Pushbot")
|
||||
@Autonomous(name="Robot: Auto Drive By Encoder", group="Robot")
|
||||
@Disabled
|
||||
public class PushbotAutoDriveByEncoder_Linear extends LinearOpMode {
|
||||
public class RobotAutoDriveByEncoder_Linear extends LinearOpMode {
|
||||
|
||||
/* Declare OpMode members. */
|
||||
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
|
||||
private DcMotor leftDrive = null;
|
||||
private DcMotor rightDrive = null;
|
||||
|
||||
private 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
|
||||
// For external drive gearing, set DRIVE_GEAR_REDUCTION as needed.
|
||||
// For example, use a value of 2.0 for a 12-tooth spur gear driving a 24-tooth spur gear.
|
||||
// This is gearing DOWN for less speed and more torque.
|
||||
// For gearing UP, use a gear ratio less than 1.0. Note this will affect the direction of wheel rotation.
|
||||
static final double COUNTS_PER_MOTOR_REV = 1440 ; // eg: TETRIX Motor Encoder
|
||||
static final double DRIVE_GEAR_REDUCTION = 2.0 ; // This is < 1.0 if geared UP
|
||||
static final double DRIVE_GEAR_REDUCTION = 1.0 ; // No External Gearing.
|
||||
static final double WHEEL_DIAMETER_INCHES = 4.0 ; // For figuring circumference
|
||||
static final double COUNTS_PER_INCH = (COUNTS_PER_MOTOR_REV * DRIVE_GEAR_REDUCTION) /
|
||||
(WHEEL_DIAMETER_INCHES * 3.1415);
|
||||
@ -81,26 +89,26 @@ public class PushbotAutoDriveByEncoder_Linear extends LinearOpMode {
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
/*
|
||||
* Initialize the drive system variables.
|
||||
* The init() method of the hardware class does all the work here
|
||||
*/
|
||||
robot.init(hardwareMap);
|
||||
// Initialize the drive system variables.
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// Send telemetry message to signify robot waiting;
|
||||
telemetry.addData("Status", "Resetting Encoders"); //
|
||||
telemetry.update();
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
leftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// Send telemetry message to indicate successful Encoder reset
|
||||
telemetry.addData("Path0", "Starting at %7d :%7d",
|
||||
robot.leftDrive.getCurrentPosition(),
|
||||
robot.rightDrive.getCurrentPosition());
|
||||
telemetry.addData("Starting at", "%7d :%7d",
|
||||
leftDrive.getCurrentPosition(),
|
||||
rightDrive.getCurrentPosition());
|
||||
telemetry.update();
|
||||
|
||||
// Wait for the game to start (driver presses PLAY)
|
||||
@ -112,12 +120,9 @@ public class PushbotAutoDriveByEncoder_Linear extends LinearOpMode {
|
||||
encoderDrive(TURN_SPEED, 12, -12, 4.0); // S2: Turn Right 12 Inches with 4 Sec timeout
|
||||
encoderDrive(DRIVE_SPEED, -24, -24, 4.0); // S3: Reverse 24 Inches with 4 Sec timeout
|
||||
|
||||
robot.leftClaw.setPosition(1.0); // S4: Stop and close the claw.
|
||||
robot.rightClaw.setPosition(0.0);
|
||||
sleep(1000); // pause for servos to move
|
||||
|
||||
telemetry.addData("Path", "Complete");
|
||||
telemetry.update();
|
||||
sleep(1000); // pause to display final telemetry message.
|
||||
}
|
||||
|
||||
/*
|
||||
@ -138,19 +143,19 @@ public class PushbotAutoDriveByEncoder_Linear extends LinearOpMode {
|
||||
if (opModeIsActive()) {
|
||||
|
||||
// Determine new target position, and pass to motor controller
|
||||
newLeftTarget = robot.leftDrive.getCurrentPosition() + (int)(leftInches * COUNTS_PER_INCH);
|
||||
newRightTarget = robot.rightDrive.getCurrentPosition() + (int)(rightInches * COUNTS_PER_INCH);
|
||||
robot.leftDrive.setTargetPosition(newLeftTarget);
|
||||
robot.rightDrive.setTargetPosition(newRightTarget);
|
||||
newLeftTarget = leftDrive.getCurrentPosition() + (int)(leftInches * COUNTS_PER_INCH);
|
||||
newRightTarget = rightDrive.getCurrentPosition() + (int)(rightInches * COUNTS_PER_INCH);
|
||||
leftDrive.setTargetPosition(newLeftTarget);
|
||||
rightDrive.setTargetPosition(newRightTarget);
|
||||
|
||||
// Turn On RUN_TO_POSITION
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
leftDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
rightDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
|
||||
// reset the timeout time and start motion.
|
||||
runtime.reset();
|
||||
robot.leftDrive.setPower(Math.abs(speed));
|
||||
robot.rightDrive.setPower(Math.abs(speed));
|
||||
leftDrive.setPower(Math.abs(speed));
|
||||
rightDrive.setPower(Math.abs(speed));
|
||||
|
||||
// keep looping while we are still active, and there is time left, and both motors are running.
|
||||
// Note: We use (isBusy() && isBusy()) in the loop test, which means that when EITHER motor hits
|
||||
@ -160,25 +165,24 @@ public class PushbotAutoDriveByEncoder_Linear extends LinearOpMode {
|
||||
// onto the next step, use (isBusy() || isBusy()) in the loop test.
|
||||
while (opModeIsActive() &&
|
||||
(runtime.seconds() < timeoutS) &&
|
||||
(robot.leftDrive.isBusy() && robot.rightDrive.isBusy())) {
|
||||
(leftDrive.isBusy() && rightDrive.isBusy())) {
|
||||
|
||||
// Display it for the driver.
|
||||
telemetry.addData("Path1", "Running to %7d :%7d", newLeftTarget, newRightTarget);
|
||||
telemetry.addData("Path2", "Running at %7d :%7d",
|
||||
robot.leftDrive.getCurrentPosition(),
|
||||
robot.rightDrive.getCurrentPosition());
|
||||
telemetry.addData("Running to", " %7d :%7d", newLeftTarget, newRightTarget);
|
||||
telemetry.addData("Currently at", " at %7d :%7d",
|
||||
leftDrive.getCurrentPosition(), rightDrive.getCurrentPosition());
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Stop all motion;
|
||||
robot.leftDrive.setPower(0);
|
||||
robot.rightDrive.setPower(0);
|
||||
leftDrive.setPower(0);
|
||||
rightDrive.setPower(0);
|
||||
|
||||
// Turn off RUN_TO_POSITION
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// sleep(250); // optional pause after each move
|
||||
sleep(250); // optional pause after each move.
|
||||
}
|
||||
}
|
||||
}
|
@ -39,14 +39,13 @@ import com.qualcomm.robotcore.util.Range;
|
||||
|
||||
/**
|
||||
* This file illustrates the concept of driving a path based on Gyro heading and encoder counts.
|
||||
* It uses the common Pushbot hardware class to define the drive on the robot.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* The code REQUIRES that you DO have encoders on the wheels,
|
||||
* otherwise you would use: PushbotAutoDriveByTime;
|
||||
* otherwise you would use: RobotAutoDriveByTime;
|
||||
*
|
||||
* This code ALSO requires that you have a Modern Robotics I2C gyro with the name "gyro"
|
||||
* otherwise you would use: PushbotAutoDriveByEncoder;
|
||||
* otherwise you would use: RobotAutoDriveByEncoder;
|
||||
*
|
||||
* This code requires that the drive Motors have been configured such that a positive
|
||||
* power command moves them forward, and causes the encoders to count UP.
|
||||
@ -62,24 +61,33 @@ import com.qualcomm.robotcore.util.Range;
|
||||
* the Gyro Calibration process, or whenever the program issues a resetZAxisIntegrator() call on the Gyro.
|
||||
*
|
||||
* The angle of movement/rotation is assumed to be a standardized rotation around the robot Z axis,
|
||||
* which means that a Positive rotation is Counter Clock Wise, looking down on the field.
|
||||
* which means that a Positive rotation is Counter Clockwise, looking down on the field.
|
||||
* This is consistent with the FTC field coordinate conventions set out in the document:
|
||||
* ftc_app\doc\tutorial\FTC_FieldCoordinateSystemDefinition.pdf
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@Autonomous(name="Pushbot: Auto Drive By Gyro", group="Pushbot")
|
||||
@Autonomous(name="Robot: Auto Drive By Gyro", group="Robot")
|
||||
@Disabled
|
||||
public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
public class RobotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
|
||||
/* Declare OpMode members. */
|
||||
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
|
||||
private DcMotor leftDrive = null;
|
||||
private DcMotor rightDrive = null;
|
||||
ModernRoboticsI2cGyro gyro = null; // Additional Gyro device
|
||||
|
||||
private double robotHeading = 0;
|
||||
|
||||
// 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
|
||||
// For external drive gearing, set DRIVE_GEAR_REDUCTION as needed.
|
||||
// For example, use a value of 2.0 for a 12-tooth spur gear driving a 24-tooth spur gear.
|
||||
// This is gearing DOWN for less speed and more torque.
|
||||
// For gearing UP, use a gear ratio less than 1.0. Note this will affect the direction of wheel rotation.
|
||||
static final double COUNTS_PER_MOTOR_REV = 1440 ; // eg: TETRIX Motor Encoder
|
||||
static final double DRIVE_GEAR_REDUCTION = 2.0 ; // This is < 1.0 if geared UP
|
||||
static final double DRIVE_GEAR_REDUCTION = 1.0 ; // No External Gearing.
|
||||
static final double WHEEL_DIAMETER_INCHES = 4.0 ; // For figuring circumference
|
||||
static final double COUNTS_PER_INCH = (COUNTS_PER_MOTOR_REV * DRIVE_GEAR_REDUCTION) /
|
||||
(WHEEL_DIAMETER_INCHES * 3.1415);
|
||||
@ -97,16 +105,21 @@ public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
/*
|
||||
* Initialize the standard drive system variables.
|
||||
* The init() method of the hardware class does most of the work here
|
||||
*/
|
||||
robot.init(hardwareMap);
|
||||
// Initialize the drive system variables.
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
gyro = (ModernRoboticsI2cGyro)hardwareMap.gyroSensor.get("gyro");
|
||||
|
||||
// Ensure the robot it stationary, then reset the encoders and calibrate the gyro.
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
leftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
|
||||
// Send telemetry message to alert driver that we are calibrating;
|
||||
telemetry.addData(">", "Calibrating Gyro"); //
|
||||
@ -123,43 +136,46 @@ public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
telemetry.addData(">", "Robot Ready."); //
|
||||
telemetry.update();
|
||||
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// Wait for the game to start (Display Gyro value), and reset gyro before we move..
|
||||
while (!isStarted()) {
|
||||
telemetry.addData(">", "Robot Heading = %d", gyro.getIntegratedZValue());
|
||||
// Wait for the game to start (Display Gyro value)
|
||||
while (opModeInInit()) {
|
||||
telemetry.addData(">", "Robot Heading = %4.0f", getHeading());
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Reset gyro before we move..
|
||||
gyro.resetZAxisIntegrator();
|
||||
getHeading();
|
||||
|
||||
// Step through each leg of the path,
|
||||
// Note: Reverse movement is obtained by setting a negative distance (not speed)
|
||||
// Put a hold after each turn
|
||||
gyroDrive(DRIVE_SPEED, 48.0, 0.0); // Drive FWD 48 inches
|
||||
gyroTurn( TURN_SPEED, -45.0); // Turn CCW to -45 Degrees
|
||||
gyroHold( TURN_SPEED, -45.0, 0.5); // Hold -45 Deg heading for a 1/2 second
|
||||
gyroDrive(DRIVE_SPEED, 48.0, 0.0); // Drive FWD 48 inches
|
||||
gyroTurn( TURN_SPEED, -45.0); // Turn CW to -45 Degrees
|
||||
gyroHold( TURN_SPEED, -45.0, 0.5); // Hold -45 Deg heading for a 1/2 second
|
||||
gyroDrive(DRIVE_SPEED, 12.0, -45.0); // Drive FWD 12 inches at 45 degrees
|
||||
gyroTurn( TURN_SPEED, 45.0); // Turn CW to 45 Degrees
|
||||
gyroTurn( TURN_SPEED, 45.0); // Turn CCW to 45 Degrees
|
||||
gyroHold( TURN_SPEED, 45.0, 0.5); // Hold 45 Deg heading for a 1/2 second
|
||||
gyroTurn( TURN_SPEED, 0.0); // Turn CW to 0 Degrees
|
||||
gyroTurn( TURN_SPEED, 0.0); // Turn CW to 0 Degrees
|
||||
gyroHold( TURN_SPEED, 0.0, 1.0); // Hold 0 Deg heading for a 1 second
|
||||
gyroDrive(DRIVE_SPEED,-48.0, 0.0); // Drive REV 48 inches
|
||||
|
||||
telemetry.addData("Path", "Complete");
|
||||
telemetry.addData("Final Heading", "%5.0f", getHeading());
|
||||
telemetry.update();
|
||||
sleep(1000); // Pause to display last telemetry message.
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Method to drive on a fixed compass bearing (angle), based on encoder counts.
|
||||
* Move will stop if either of these conditions occur:
|
||||
* 1) Move gets to the desired position
|
||||
* 2) Driver stops the opmode running.
|
||||
*
|
||||
* @param speed Target speed for forward motion. Should allow for _/- variance for adjusting heading
|
||||
* @param distance Distance (in inches) to move from current position. Negative distance means move backwards.
|
||||
* @param speed Target speed for forward motion. Should allow for +/- variance for adjusting heading
|
||||
* @param distance Distance (in inches) to move from current position. Negative distance means move backward.
|
||||
* @param angle Absolute Angle (in Degrees) relative to last gyro reset.
|
||||
* 0 = fwd. +ve is CCW from fwd. -ve is CW from forward.
|
||||
* If a relative angle is required, add/subtract from current heading.
|
||||
@ -182,24 +198,24 @@ public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
|
||||
// Determine new target position, and pass to motor controller
|
||||
moveCounts = (int)(distance * COUNTS_PER_INCH);
|
||||
newLeftTarget = robot.leftDrive.getCurrentPosition() + moveCounts;
|
||||
newRightTarget = robot.rightDrive.getCurrentPosition() + moveCounts;
|
||||
newLeftTarget = leftDrive.getCurrentPosition() + moveCounts;
|
||||
newRightTarget = rightDrive.getCurrentPosition() + moveCounts;
|
||||
|
||||
// Set Target and Turn On RUN_TO_POSITION
|
||||
robot.leftDrive.setTargetPosition(newLeftTarget);
|
||||
robot.rightDrive.setTargetPosition(newRightTarget);
|
||||
leftDrive.setTargetPosition(newLeftTarget);
|
||||
rightDrive.setTargetPosition(newRightTarget);
|
||||
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
leftDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
rightDrive.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||
|
||||
// start motion.
|
||||
speed = Range.clip(Math.abs(speed), 0.0, 1.0);
|
||||
robot.leftDrive.setPower(speed);
|
||||
robot.rightDrive.setPower(speed);
|
||||
leftDrive.setPower(speed);
|
||||
rightDrive.setPower(speed);
|
||||
|
||||
// keep looping while we are still active, and BOTH motors are running.
|
||||
while (opModeIsActive() &&
|
||||
(robot.leftDrive.isBusy() && robot.rightDrive.isBusy())) {
|
||||
(leftDrive.isBusy() && rightDrive.isBusy())) {
|
||||
|
||||
// adjust relative speed based on heading error.
|
||||
error = getError(angle);
|
||||
@ -220,25 +236,26 @@ public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
rightSpeed /= max;
|
||||
}
|
||||
|
||||
robot.leftDrive.setPower(leftSpeed);
|
||||
robot.rightDrive.setPower(rightSpeed);
|
||||
leftDrive.setPower(leftSpeed);
|
||||
rightDrive.setPower(rightSpeed);
|
||||
|
||||
// Display drive status for the driver.
|
||||
telemetry.addData("Err/St", "%5.1f/%5.1f", error, steer);
|
||||
telemetry.addData("Target", "%7d:%7d", newLeftTarget, newRightTarget);
|
||||
telemetry.addData("Actual", "%7d:%7d", robot.leftDrive.getCurrentPosition(),
|
||||
robot.rightDrive.getCurrentPosition());
|
||||
telemetry.addData("Speed", "%5.2f:%5.2f", leftSpeed, rightSpeed);
|
||||
telemetry.addData("Angle Target:Current", "%5.2f:%5.0f", angle, robotHeading);
|
||||
telemetry.addData("Error:Steer", "%5.1f:%5.1f", error, steer);
|
||||
telemetry.addData("Target L:R", "%7d:%7d", newLeftTarget, newRightTarget);
|
||||
telemetry.addData("Actual L:R", "%7d:%7d", leftDrive.getCurrentPosition(),
|
||||
rightDrive.getCurrentPosition());
|
||||
telemetry.addData("Speed L:R", "%5.2f:%5.2f", leftSpeed, rightSpeed);
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Stop all motion;
|
||||
robot.leftDrive.setPower(0);
|
||||
robot.rightDrive.setPower(0);
|
||||
leftDrive.setPower(0);
|
||||
rightDrive.setPower(0);
|
||||
|
||||
// Turn off RUN_TO_POSITION
|
||||
robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
}
|
||||
}
|
||||
|
||||
@ -285,8 +302,8 @@ public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
}
|
||||
|
||||
// Stop all motion;
|
||||
robot.leftDrive.setPower(0);
|
||||
robot.rightDrive.setPower(0);
|
||||
leftDrive.setPower(0);
|
||||
rightDrive.setPower(0);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -322,13 +339,13 @@ public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
}
|
||||
|
||||
// Send desired speeds to motors.
|
||||
robot.leftDrive.setPower(leftSpeed);
|
||||
robot.rightDrive.setPower(rightSpeed);
|
||||
leftDrive.setPower(leftSpeed);
|
||||
rightDrive.setPower(rightSpeed);
|
||||
|
||||
// Display it for the driver.
|
||||
telemetry.addData("Target", "%5.2f", angle);
|
||||
telemetry.addData("Err/St", "%5.2f/%5.2f", error, steer);
|
||||
telemetry.addData("Speed.", "%5.2f:%5.2f", leftSpeed, rightSpeed);
|
||||
telemetry.addData("Target/Current", "%5.2f / %5.0f", angle, robotHeading);
|
||||
telemetry.addData("Error/Steer", "%5.2f / %5.2f", error, steer);
|
||||
telemetry.addData("Speed.", "%5.2f : %5.2f", leftSpeed, rightSpeed);
|
||||
|
||||
return onTarget;
|
||||
}
|
||||
@ -344,12 +361,20 @@ public class PushbotAutoDriveByGyro_Linear extends LinearOpMode {
|
||||
double robotError;
|
||||
|
||||
// calculate error in -179 to +180 range (
|
||||
robotError = targetAngle - gyro.getIntegratedZValue();
|
||||
robotError = targetAngle - getHeading();
|
||||
while (robotError > 180) robotError -= 360;
|
||||
while (robotError <= -180) robotError += 360;
|
||||
return robotError;
|
||||
}
|
||||
|
||||
/**
|
||||
* read and save the current robot heading
|
||||
*/
|
||||
public double getHeading() {
|
||||
robotHeading = (double)gyro.getIntegratedZValue();
|
||||
return robotHeading;
|
||||
}
|
||||
|
||||
/**
|
||||
* returns desired steering force. +/- 1 range. +ve = steer left
|
||||
* @param error Error angle in robot relative degrees
|
@ -32,35 +32,36 @@ package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
/**
|
||||
* This file illustrates the concept of driving a path based on time.
|
||||
* It uses the common Pushbot hardware class to define the drive on the robot.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* The code assumes that you do NOT have encoders on the wheels,
|
||||
* otherwise you would use: PushbotAutoDriveByEncoder;
|
||||
* otherwise you would use: RobotAutoDriveByEncoder;
|
||||
*
|
||||
* The desired path in this example is:
|
||||
* - Drive forward for 3 seconds
|
||||
* - Spin right for 1.3 seconds
|
||||
* - Drive Backwards for 1 Second
|
||||
* - Stop and close the claw.
|
||||
* - Drive Backward for 1 Second
|
||||
*
|
||||
* The code is written in a simple form with no optimizations.
|
||||
* However, there are several ways that this type of sequence could be streamlined,
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@Autonomous(name="Pushbot: Auto Drive By Time", group="Pushbot")
|
||||
@Autonomous(name="Robot: Auto Drive By Time", group="Robot")
|
||||
@Disabled
|
||||
public class PushbotAutoDriveByTime_Linear extends LinearOpMode {
|
||||
public class RobotAutoDriveByTime_Linear extends LinearOpMode {
|
||||
|
||||
/* Declare OpMode members. */
|
||||
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
|
||||
private DcMotor leftDrive = null;
|
||||
private DcMotor rightDrive = null;
|
||||
|
||||
private ElapsedTime runtime = new ElapsedTime();
|
||||
|
||||
|
||||
@ -70,11 +71,15 @@ public class PushbotAutoDriveByTime_Linear extends LinearOpMode {
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
/*
|
||||
* Initialize the drive system variables.
|
||||
* The init() method of the hardware class does all the work here
|
||||
*/
|
||||
robot.init(hardwareMap);
|
||||
// Initialize the drive system variables.
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
// Send telemetry message to signify robot waiting;
|
||||
telemetry.addData("Status", "Ready to run"); //
|
||||
@ -86,37 +91,35 @@ public class PushbotAutoDriveByTime_Linear extends LinearOpMode {
|
||||
// Step through each leg of the path, ensuring that the Auto mode has not been stopped along the way
|
||||
|
||||
// Step 1: Drive forward for 3 seconds
|
||||
robot.leftDrive.setPower(FORWARD_SPEED);
|
||||
robot.rightDrive.setPower(FORWARD_SPEED);
|
||||
leftDrive.setPower(FORWARD_SPEED);
|
||||
rightDrive.setPower(FORWARD_SPEED);
|
||||
runtime.reset();
|
||||
while (opModeIsActive() && (runtime.seconds() < 3.0)) {
|
||||
telemetry.addData("Path", "Leg 1: %2.5f S Elapsed", runtime.seconds());
|
||||
telemetry.addData("Path", "Leg 1: %4.1f S Elapsed", runtime.seconds());
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Step 2: Spin right for 1.3 seconds
|
||||
robot.leftDrive.setPower(TURN_SPEED);
|
||||
robot.rightDrive.setPower(-TURN_SPEED);
|
||||
leftDrive.setPower(TURN_SPEED);
|
||||
rightDrive.setPower(-TURN_SPEED);
|
||||
runtime.reset();
|
||||
while (opModeIsActive() && (runtime.seconds() < 1.3)) {
|
||||
telemetry.addData("Path", "Leg 2: %2.5f S Elapsed", runtime.seconds());
|
||||
telemetry.addData("Path", "Leg 2: %4.1f S Elapsed", runtime.seconds());
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Step 3: Drive Backwards for 1 Second
|
||||
robot.leftDrive.setPower(-FORWARD_SPEED);
|
||||
robot.rightDrive.setPower(-FORWARD_SPEED);
|
||||
// Step 3: Drive Backward for 1 Second
|
||||
leftDrive.setPower(-FORWARD_SPEED);
|
||||
rightDrive.setPower(-FORWARD_SPEED);
|
||||
runtime.reset();
|
||||
while (opModeIsActive() && (runtime.seconds() < 1.0)) {
|
||||
telemetry.addData("Path", "Leg 3: %2.5f S Elapsed", runtime.seconds());
|
||||
telemetry.addData("Path", "Leg 3: %4.1f S Elapsed", runtime.seconds());
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Step 4: Stop and close the claw.
|
||||
robot.leftDrive.setPower(0);
|
||||
robot.rightDrive.setPower(0);
|
||||
robot.leftClaw.setPosition(1.0);
|
||||
robot.rightClaw.setPosition(0.0);
|
||||
// Step 4: Stop
|
||||
leftDrive.setPower(0);
|
||||
rightDrive.setPower(0);
|
||||
|
||||
telemetry.addData("Path", "Complete");
|
||||
telemetry.update();
|
@ -0,0 +1,144 @@
|
||||
/* Copyright (c) 2017 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.hardware.ColorSensor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.LightSensor;
|
||||
import com.qualcomm.robotcore.hardware.NormalizedColorSensor;
|
||||
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||
import com.qualcomm.robotcore.hardware.SwitchableLight;
|
||||
|
||||
/**
|
||||
* This file illustrates the concept of driving up to a line and then stopping.
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* The Sensor used here can be a REV Color Sensor V2 or V3. Make sure the white LED is turned on.
|
||||
* The sensor can be plugged into any I2C port, and must be named "sensor_color" in the active configuration.
|
||||
*
|
||||
* Depending on the height of your color sensor, you may want to set the sensor "gain".
|
||||
* The higher the gain, the greater the reflected light reading will be.
|
||||
* Use the SensorColor sample in this folder to determine the minimum gain value that provides an
|
||||
* "Alpha" reading of 1.0 when you are on top of the white line. In this sample, we use a gain of 15
|
||||
* which works well with a Rev V2 color sensor
|
||||
*
|
||||
* Setting the correct WHITE_THRESHOLD value is key to stopping correctly.
|
||||
* This should be set halfway between the bare-tile, and white-line "Alpha" values.
|
||||
* The reflected light value can be read on the screen once the OpMode has been INIT, but before it is STARTED.
|
||||
* Move the sensor on and off the white line and note the min and max readings.
|
||||
* Edit this code to make WHITE_THRESHOLD halfway between the min and max.
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@Autonomous(name="Robot: Auto Drive To Line", group="Robot")
|
||||
@Disabled
|
||||
public class RobotAutoDriveToLine_Linear extends LinearOpMode {
|
||||
|
||||
/* Declare OpMode members. */
|
||||
private DcMotor leftDrive = null;
|
||||
private DcMotor rightDrive = null;
|
||||
|
||||
/** The colorSensor field will contain a reference to our color sensor hardware object */
|
||||
NormalizedColorSensor colorSensor;
|
||||
|
||||
static final double WHITE_THRESHOLD = 0.5; // spans between 0.0 - 1.0 from dark to light
|
||||
static final double APPROACH_SPEED = 0.25;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
// Initialize the drive system variables.
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
// If there are encoders connected, switch to RUN_USING_ENCODER mode for greater accuracy
|
||||
// robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
// robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// Get a reference to our sensor object. It's recommended to use NormalizedColorSensor over
|
||||
// ColorSensor, because NormalizedColorSensor consistently gives values between 0 and 1, while
|
||||
// the values you get from ColorSensor are dependent on the specific sensor you're using.
|
||||
colorSensor = hardwareMap.get(NormalizedColorSensor.class, "sensor_color");
|
||||
|
||||
// If necessary, turn ON the white LED (if there is no LED switch on the sensor)
|
||||
if (colorSensor instanceof SwitchableLight) {
|
||||
((SwitchableLight)colorSensor).enableLight(true);
|
||||
}
|
||||
|
||||
// Some sensors allow you to set your light sensor gain for optimal sensitivity...
|
||||
// See the SensorColor sample in this folder for how to determine the optimal gain.
|
||||
// A gain of 15 causes a Rev Color Sensor V2 to produce an Alpha value of 1.0 at about 1.5" above the floor.
|
||||
colorSensor.setGain(15);
|
||||
|
||||
// Wait for driver to press PLAY)
|
||||
// Abort this loop is started or stopped.
|
||||
while (opModeInInit()) {
|
||||
|
||||
// Send telemetry message to signify robot waiting;
|
||||
telemetry.addData("Status", "Ready to drive to white line."); //
|
||||
|
||||
// Display the light level while we are waiting to start
|
||||
getBrightness();
|
||||
}
|
||||
|
||||
// Start the robot moving forward, and then begin looking for a white line.
|
||||
leftDrive.setPower(APPROACH_SPEED);
|
||||
rightDrive.setPower(APPROACH_SPEED);
|
||||
|
||||
// run until the white line is seen OR the driver presses STOP;
|
||||
while (opModeIsActive() && (getBrightness() < WHITE_THRESHOLD)) {
|
||||
sleep(5);
|
||||
}
|
||||
|
||||
// Stop all motors
|
||||
leftDrive.setPower(0);
|
||||
rightDrive.setPower(0);
|
||||
}
|
||||
|
||||
// to obtain reflected light, read the normalized values from the color sensor. Return the Alpha channel.
|
||||
double getBrightness() {
|
||||
NormalizedRGBA colors = colorSensor.getNormalizedColors();
|
||||
telemetry.addData("Light Level (0 to 1)", "%4.2f", colors.alpha);
|
||||
telemetry.update();
|
||||
|
||||
return colors.alpha;
|
||||
}
|
||||
}
|
@ -32,30 +32,39 @@ package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
import com.qualcomm.robotcore.util.Range;
|
||||
|
||||
/**
|
||||
* This OpMode uses the common Pushbot hardware class to define the devices on the robot.
|
||||
* All device access is managed through the HardwarePushbot class.
|
||||
* This particular OpMode executes a POV Game style Teleop for a direct drive robot
|
||||
* The code is structured as a LinearOpMode
|
||||
*
|
||||
* This particular OpMode executes a POV Game style Teleop for a PushBot
|
||||
* In this mode the left stick moves the robot FWD and back, the Right stick turns left and right.
|
||||
* It raises and lowers the claw using the Gampad Y and A buttons respectively.
|
||||
* It raises and lowers the arm using the Gamepad Y and A buttons respectively.
|
||||
* It also opens and closes the claws slowly using the left and right Bumper buttons.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@TeleOp(name="Pushbot: Teleop POV", group="Pushbot")
|
||||
@TeleOp(name="Robot: Teleop POV", group="Robot")
|
||||
@Disabled
|
||||
public class PushbotTeleopPOV_Linear extends LinearOpMode {
|
||||
public class RobotTeleopPOV_Linear extends LinearOpMode {
|
||||
|
||||
/* Declare OpMode members. */
|
||||
HardwarePushbot robot = new HardwarePushbot(); // Use a Pushbot's hardware
|
||||
double clawOffset = 0; // Servo mid position
|
||||
final double CLAW_SPEED = 0.02 ; // sets rate to move servo
|
||||
public DcMotor leftDrive = null;
|
||||
public DcMotor rightDrive = null;
|
||||
public DcMotor leftArm = null;
|
||||
public Servo leftClaw = null;
|
||||
public Servo rightClaw = null;
|
||||
|
||||
double clawOffset = 0;
|
||||
|
||||
public static final double MID_SERVO = 0.5 ;
|
||||
public static final double CLAW_SPEED = 0.02 ; // sets rate to move servo
|
||||
public static final double ARM_UP_POWER = 0.45 ;
|
||||
public static final double ARM_DOWN_POWER = -0.45 ;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
@ -65,10 +74,26 @@ public class PushbotTeleopPOV_Linear extends LinearOpMode {
|
||||
double turn;
|
||||
double max;
|
||||
|
||||
/* Initialize the hardware variables.
|
||||
* The init() method of the hardware class does all the work here
|
||||
*/
|
||||
robot.init(hardwareMap);
|
||||
// Define and Initialize Motors
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
leftArm = hardwareMap.get(DcMotor.class, "left_arm");
|
||||
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// Pushing the left stick forward MUST make robot go forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
// If there are encoders connected, switch to RUN_USING_ENCODER mode for greater accuracy
|
||||
// robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
// robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// Define and initialize ALL installed servos.
|
||||
leftClaw = hardwareMap.get(Servo.class, "left_hand");
|
||||
rightClaw = hardwareMap.get(Servo.class, "right_hand");
|
||||
leftClaw.setPosition(MID_SERVO);
|
||||
rightClaw.setPosition(MID_SERVO);
|
||||
|
||||
// Send telemetry message to signify robot waiting;
|
||||
telemetry.addData("Say", "Hello Driver"); //
|
||||
@ -80,7 +105,7 @@ public class PushbotTeleopPOV_Linear extends LinearOpMode {
|
||||
// run until the end of the match (driver presses STOP)
|
||||
while (opModeIsActive()) {
|
||||
|
||||
// Run wheels in POV mode (note: The joystick goes negative when pushed forwards, so negate it)
|
||||
// Run wheels in POV mode (note: The joystick goes negative when pushed forward, so negate it)
|
||||
// In this mode the Left stick moves the robot fwd and back, the Right stick turns left and right.
|
||||
// This way it's also easy to just drive straight, or just turn.
|
||||
drive = -gamepad1.left_stick_y;
|
||||
@ -99,8 +124,8 @@ public class PushbotTeleopPOV_Linear extends LinearOpMode {
|
||||
}
|
||||
|
||||
// Output the safe vales to the motor drives.
|
||||
robot.leftDrive.setPower(left);
|
||||
robot.rightDrive.setPower(right);
|
||||
leftDrive.setPower(left);
|
||||
rightDrive.setPower(right);
|
||||
|
||||
// Use gamepad left & right Bumpers to open and close the claw
|
||||
if (gamepad1.right_bumper)
|
||||
@ -110,16 +135,16 @@ public class PushbotTeleopPOV_Linear extends LinearOpMode {
|
||||
|
||||
// Move both servos to new position. Assume servos are mirror image of each other.
|
||||
clawOffset = Range.clip(clawOffset, -0.5, 0.5);
|
||||
robot.leftClaw.setPosition(robot.MID_SERVO + clawOffset);
|
||||
robot.rightClaw.setPosition(robot.MID_SERVO - clawOffset);
|
||||
leftClaw.setPosition(MID_SERVO + clawOffset);
|
||||
rightClaw.setPosition(MID_SERVO - clawOffset);
|
||||
|
||||
// Use gamepad buttons to move arm up (Y) and down (A)
|
||||
if (gamepad1.y)
|
||||
robot.leftArm.setPower(robot.ARM_UP_POWER);
|
||||
leftArm.setPower(ARM_UP_POWER);
|
||||
else if (gamepad1.a)
|
||||
robot.leftArm.setPower(robot.ARM_DOWN_POWER);
|
||||
leftArm.setPower(ARM_DOWN_POWER);
|
||||
else
|
||||
robot.leftArm.setPower(0.0);
|
||||
leftArm.setPower(0.0);
|
||||
|
||||
// Send telemetry message to signify robot running;
|
||||
telemetry.addData("claw", "Offset = %.2f", clawOffset);
|
@ -32,41 +32,66 @@ package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
import com.qualcomm.robotcore.util.Range;
|
||||
|
||||
/**
|
||||
* This file provides basic Telop driving for a Pushbot robot.
|
||||
* This particular OpMode executes a Tank Drive control TeleOp a direct drive robot
|
||||
* The code is structured as an Iterative OpMode
|
||||
*
|
||||
* This OpMode uses the common Pushbot hardware class to define the devices on the robot.
|
||||
* All device access is managed through the HardwarePushbot class.
|
||||
*
|
||||
* This particular OpMode executes a basic Tank Drive Teleop for a PushBot
|
||||
* It raises and lowers the claw using the Gampad Y and A buttons respectively.
|
||||
* In this mode, the left and right joysticks control the left and right motors respectively.
|
||||
* Pushing a joystick forward will make the attached motor drive forward.
|
||||
* It raises and lowers the claw using the Gamepad Y and A buttons respectively.
|
||||
* It also opens and closes the claws slowly using the left and right Bumper buttons.
|
||||
*
|
||||
* Use Android Studios to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
|
||||
*/
|
||||
|
||||
@TeleOp(name="Pushbot: Teleop Tank", group="Pushbot")
|
||||
@TeleOp(name="Robot: Teleop Tank", group="Robot")
|
||||
@Disabled
|
||||
public class PushbotTeleopTank_Iterative extends OpMode{
|
||||
public class RobotTeleopTank_Iterative extends OpMode{
|
||||
|
||||
/* Declare OpMode members. */
|
||||
HardwarePushbot robot = new HardwarePushbot(); // use the class created to define a Pushbot's hardware
|
||||
double clawOffset = 0.0 ; // Servo mid position
|
||||
final double CLAW_SPEED = 0.02 ; // sets rate to move servo
|
||||
public DcMotor leftDrive = null;
|
||||
public DcMotor rightDrive = null;
|
||||
public DcMotor leftArm = null;
|
||||
public Servo leftClaw = null;
|
||||
public Servo rightClaw = null;
|
||||
|
||||
double clawOffset = 0;
|
||||
|
||||
public static final double MID_SERVO = 0.5 ;
|
||||
public static final double CLAW_SPEED = 0.02 ; // sets rate to move servo
|
||||
public static final double ARM_UP_POWER = 0.50 ; // Run arm motor up at 50% power
|
||||
public static final double ARM_DOWN_POWER = -0.25 ; // Run arm motor down at -25% power
|
||||
|
||||
/*
|
||||
* Code to run ONCE when the driver hits INIT
|
||||
*/
|
||||
@Override
|
||||
public void init() {
|
||||
/* Initialize the hardware variables.
|
||||
* The init() method of the hardware class does all the work here
|
||||
*/
|
||||
robot.init(hardwareMap);
|
||||
// Define and Initialize Motors
|
||||
leftDrive = hardwareMap.get(DcMotor.class, "left_drive");
|
||||
rightDrive = hardwareMap.get(DcMotor.class, "right_drive");
|
||||
leftArm = hardwareMap.get(DcMotor.class, "left_arm");
|
||||
|
||||
// To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions.
|
||||
// Pushing the left and right sticks forward MUST make robot go forward. So adjust these two lines based on your first test drive.
|
||||
// Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips
|
||||
leftDrive.setDirection(DcMotor.Direction.REVERSE);
|
||||
rightDrive.setDirection(DcMotor.Direction.FORWARD);
|
||||
|
||||
// If there are encoders connected, switch to RUN_USING_ENCODER mode for greater accuracy
|
||||
// robot.leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
// robot.rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// Define and initialize ALL installed servos.
|
||||
leftClaw = hardwareMap.get(Servo.class, "left_hand");
|
||||
rightClaw = hardwareMap.get(Servo.class, "right_hand");
|
||||
leftClaw.setPosition(MID_SERVO);
|
||||
rightClaw.setPosition(MID_SERVO);
|
||||
|
||||
// Send telemetry message to signify robot waiting;
|
||||
telemetry.addData("Say", "Hello Driver"); //
|
||||
@ -94,12 +119,12 @@ public class PushbotTeleopTank_Iterative extends OpMode{
|
||||
double left;
|
||||
double right;
|
||||
|
||||
// Run wheels in tank mode (note: The joystick goes negative when pushed forwards, so negate it)
|
||||
// Run wheels in tank mode (note: The joystick goes negative when pushed forward, so negate it)
|
||||
left = -gamepad1.left_stick_y;
|
||||
right = -gamepad1.right_stick_y;
|
||||
|
||||
robot.leftDrive.setPower(left);
|
||||
robot.rightDrive.setPower(right);
|
||||
leftDrive.setPower(left);
|
||||
rightDrive.setPower(right);
|
||||
|
||||
// Use gamepad left & right Bumpers to open and close the claw
|
||||
if (gamepad1.right_bumper)
|
||||
@ -109,16 +134,16 @@ public class PushbotTeleopTank_Iterative extends OpMode{
|
||||
|
||||
// Move both servos to new position. Assume servos are mirror image of each other.
|
||||
clawOffset = Range.clip(clawOffset, -0.5, 0.5);
|
||||
robot.leftClaw.setPosition(robot.MID_SERVO + clawOffset);
|
||||
robot.rightClaw.setPosition(robot.MID_SERVO - clawOffset);
|
||||
leftClaw.setPosition(MID_SERVO + clawOffset);
|
||||
rightClaw.setPosition(MID_SERVO - clawOffset);
|
||||
|
||||
// Use gamepad buttons to move the arm up (Y) and down (A)
|
||||
if (gamepad1.y)
|
||||
robot.leftArm.setPower(robot.ARM_UP_POWER);
|
||||
leftArm.setPower(ARM_UP_POWER);
|
||||
else if (gamepad1.a)
|
||||
robot.leftArm.setPower(robot.ARM_DOWN_POWER);
|
||||
leftArm.setPower(ARM_DOWN_POWER);
|
||||
else
|
||||
robot.leftArm.setPower(0.0);
|
||||
leftArm.setPower(0.0);
|
||||
|
||||
// Send telemetry message to signify robot running;
|
||||
telemetry.addData("claw", "Offset = %.2f", clawOffset);
|
@ -1,167 +0,0 @@
|
||||
/* Copyright (c) 2017 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import android.app.Activity;
|
||||
import android.graphics.Color;
|
||||
import android.view.View;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.ColorSensor;
|
||||
import com.qualcomm.robotcore.hardware.DeviceInterfaceModule;
|
||||
import com.qualcomm.robotcore.hardware.DigitalChannel;
|
||||
|
||||
/*
|
||||
*
|
||||
* This is an example LinearOpMode that shows how to use
|
||||
* the Adafruit RGB Sensor. It assumes that the I2C
|
||||
* cable for the sensor is connected to an I2C port on the
|
||||
* Core Device Interface Module.
|
||||
*
|
||||
* It also assuems that the LED pin of the sensor is connected
|
||||
* to the digital signal pin of a digital port on the
|
||||
* Core Device Interface Module.
|
||||
*
|
||||
* You can use the digital port to turn the sensor's onboard
|
||||
* LED on or off.
|
||||
*
|
||||
* The op mode assumes that the Core Device Interface Module
|
||||
* is configured with a name of "dim" and that the Adafruit color sensor
|
||||
* is configured as an I2C device with a name of "sensor_color".
|
||||
*
|
||||
* It also assumes that the LED pin of the RGB sensor
|
||||
* is connected to the signal pin of digital port #5 (zero indexed)
|
||||
* of the Core Device Interface Module.
|
||||
*
|
||||
* You can use the X button on gamepad1 to toggle the LED on and off.
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
@TeleOp(name = "Sensor: AdafruitRGB", group = "Sensor")
|
||||
@Disabled // Comment this out to add to the opmode list
|
||||
public class SensorAdafruitRGB extends LinearOpMode {
|
||||
|
||||
ColorSensor sensorRGB;
|
||||
DeviceInterfaceModule cdim;
|
||||
|
||||
// we assume that the LED pin of the RGB sensor is connected to
|
||||
// digital port 5 (zero indexed).
|
||||
static final int LED_CHANNEL = 5;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
// hsvValues is an array that will hold the hue, saturation, and value information.
|
||||
float hsvValues[] = {0F,0F,0F};
|
||||
|
||||
// values is a reference to the hsvValues array.
|
||||
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.
|
||||
int relativeLayoutId = hardwareMap.appContext.getResources().getIdentifier("RelativeLayout", "id", hardwareMap.appContext.getPackageName());
|
||||
final View relativeLayout = ((Activity) hardwareMap.appContext).findViewById(relativeLayoutId);
|
||||
|
||||
// bPrevState and bCurrState represent the previous and current state of the button.
|
||||
boolean bPrevState = false;
|
||||
boolean bCurrState = false;
|
||||
|
||||
// bLedOn represents the state of the LED.
|
||||
boolean bLedOn = true;
|
||||
|
||||
// get a reference to our DeviceInterfaceModule object.
|
||||
cdim = hardwareMap.deviceInterfaceModule.get("dim");
|
||||
|
||||
// set the digital channel to output mode.
|
||||
// remember, the Adafruit sensor is actually two devices.
|
||||
// It's an I2C sensor and it's also an LED that can be turned on or off.
|
||||
cdim.setDigitalChannelMode(LED_CHANNEL, DigitalChannel.Mode.OUTPUT);
|
||||
|
||||
// get a reference to our ColorSensor object.
|
||||
sensorRGB = hardwareMap.colorSensor.get("sensor_color");
|
||||
|
||||
// turn the LED on in the beginning, just so user will know that the sensor is active.
|
||||
cdim.setDigitalChannelState(LED_CHANNEL, bLedOn);
|
||||
|
||||
// wait for the start button to be pressed.
|
||||
waitForStart();
|
||||
|
||||
// loop and read the RGB data.
|
||||
// Note we use opModeIsActive() as our loop condition because it is an interruptible method.
|
||||
while (opModeIsActive()) {
|
||||
|
||||
// check the status of the x button on gamepad.
|
||||
bCurrState = gamepad1.x;
|
||||
|
||||
// check for button-press state transitions.
|
||||
if ((bCurrState == true) && (bCurrState != bPrevState)) {
|
||||
|
||||
// button is transitioning to a pressed state. Toggle the LED.
|
||||
bLedOn = !bLedOn;
|
||||
cdim.setDigitalChannelState(LED_CHANNEL, bLedOn);
|
||||
}
|
||||
|
||||
// update previous state variable.
|
||||
bPrevState = bCurrState;
|
||||
|
||||
// convert the RGB values to HSV values.
|
||||
Color.RGBToHSV((sensorRGB.red() * 255) / 800, (sensorRGB.green() * 255) / 800, (sensorRGB.blue() * 255) / 800, hsvValues);
|
||||
|
||||
// send the info back to driver station using telemetry function.
|
||||
telemetry.addData("LED", bLedOn ? "On" : "Off");
|
||||
telemetry.addData("Clear", sensorRGB.alpha());
|
||||
telemetry.addData("Red ", sensorRGB.red());
|
||||
telemetry.addData("Green", sensorRGB.green());
|
||||
telemetry.addData("Blue ", sensorRGB.blue());
|
||||
telemetry.addData("Hue", hsvValues[0]);
|
||||
|
||||
// change the background color to match the color detected by the RGB sensor.
|
||||
// pass a reference to the hue, saturation, and value array as an argument
|
||||
// to the HSVToColor method.
|
||||
relativeLayout.post(new Runnable() {
|
||||
public void run() {
|
||||
relativeLayout.setBackgroundColor(Color.HSVToColor(0xff, values));
|
||||
}
|
||||
});
|
||||
|
||||
telemetry.update();
|
||||
}
|
||||
|
||||
// Set the panel back to the default color
|
||||
relativeLayout.post(new Runnable() {
|
||||
public void run() {
|
||||
relativeLayout.setBackgroundColor(Color.WHITE);
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
@ -1,107 +0,0 @@
|
||||
/* Copyright (c) 2017 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.robotcontroller.external.samples;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.DeviceInterfaceModule;
|
||||
import com.qualcomm.robotcore.hardware.DigitalChannel;
|
||||
|
||||
/*
|
||||
* This is an example LinearOpMode that shows how to use the digital inputs and outputs on the
|
||||
* the Modern Robotics Device Interface Module. In addition, it shows how to use the Red and Blue LED
|
||||
*
|
||||
* This op mode assumes that there is a Device Interface Module attached, named 'dim'.
|
||||
* On this DIM there is a digital input named 'digin' and an output named 'digout'
|
||||
*
|
||||
* To fully exercise this sample, connect pin 3 of the digin connector to pin 3 of the digout.
|
||||
* Note: Pin 1 is indicated by the black stripe, so pin 3 is at the opposite end.
|
||||
*
|
||||
* The X button on the gamepad will be used to activate the digital output pin.
|
||||
* The Red/Blue LED will be used to indicate the state of the digital input pin.
|
||||
* Blue = false (0V), Red = true (5V)
|
||||
* If the two pins are linked, the gamepad will change the LED color.
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
*/
|
||||
@TeleOp(name = "Sensor: DIM DIO", group = "Sensor")
|
||||
@Disabled
|
||||
public class SensorDIO extends LinearOpMode {
|
||||
|
||||
final int BLUE_LED_CHANNEL = 0;
|
||||
final int RED_LED_CHANNEL = 1;
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
boolean inputPin; // Input State
|
||||
boolean outputPin; // Output State
|
||||
DeviceInterfaceModule dim; // Device Object
|
||||
DigitalChannel digIn; // Device Object
|
||||
DigitalChannel digOut; // Device Object
|
||||
|
||||
// get a reference to a Modern Robotics DIM, and IO channels.
|
||||
dim = hardwareMap.get(DeviceInterfaceModule.class, "dim"); // Use generic form of device mapping
|
||||
digIn = hardwareMap.get(DigitalChannel.class, "digin"); // Use generic form of device mapping
|
||||
digOut = hardwareMap.get(DigitalChannel.class, "digout"); // Use generic form of device mapping
|
||||
|
||||
digIn.setMode(DigitalChannel.Mode.INPUT); // Set the direction of each channel
|
||||
digOut.setMode(DigitalChannel.Mode.OUTPUT);
|
||||
|
||||
// wait for the start button to be pressed.
|
||||
telemetry.addData(">", "Press play, and then user X button to set DigOut");
|
||||
telemetry.update();
|
||||
waitForStart();
|
||||
|
||||
while (opModeIsActive()) {
|
||||
|
||||
outputPin = gamepad1.x ; // Set the output pin based on x button
|
||||
digOut.setState(outputPin);
|
||||
inputPin = digIn.getState(); // Read the input pin
|
||||
|
||||
// Display input pin state on LEDs
|
||||
if (inputPin) {
|
||||
dim.setLED(RED_LED_CHANNEL, true);
|
||||
dim.setLED(BLUE_LED_CHANNEL, false);
|
||||
}
|
||||
else {
|
||||
dim.setLED(RED_LED_CHANNEL, false);
|
||||
dim.setLED(BLUE_LED_CHANNEL, true);
|
||||
}
|
||||
|
||||
telemetry.addData("Output", outputPin );
|
||||
telemetry.addData("Input", inputPin );
|
||||
telemetry.addData("LED", inputPin ? "Red" : "Blue" );
|
||||
telemetry.update();
|
||||
}
|
||||
}
|
||||
}
|
@ -49,7 +49,7 @@ import com.qualcomm.robotcore.hardware.ColorSensor;
|
||||
* You can use the X button on gamepad1 to toggle the LED on and off.
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
|
||||
*/
|
||||
@TeleOp(name = "Sensor: MR Color", group = "Sensor")
|
||||
@Disabled
|
||||
|
@ -49,7 +49,7 @@ import org.firstinspires.ftc.robotcore.external.navigation.AxesReference;
|
||||
* I2C channel and is configured with a name of "gyro".
|
||||
*
|
||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
||||
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list
|
||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
|
||||
*/
|
||||
@TeleOp(name = "Sensor: MR Gyro", group = "Sensor")
|
||||
@Disabled
|
||||
@ -83,7 +83,7 @@ public class SensorMRGyro extends LinearOpMode {
|
||||
// A similar approach will work for the Gyroscope interface, if that's all you need.
|
||||
|
||||
// Start calibrating the gyro. This takes a few seconds and is worth performing
|
||||
// during the initialization phase at the start of each opMode.
|
||||
// during the initialization phase at the start of each OpMode.
|
||||
telemetry.log().add("Gyro Calibrating. Do Not Move!");
|
||||
modernRoboticsI2cGyro.calibrate();
|
||||
|
||||
|
@ -27,15 +27,9 @@ Sensor: This is a Sample OpMode that shows how to use a specific sensor.
|
||||
It is not intended to drive a functioning robot, it is simply showing the minimal code
|
||||
required to read and display the sensor values.
|
||||
|
||||
Hardware: This is NOT an OpMode, but a helper class that is used to describe
|
||||
one particular robot's hardware configuration: eg: For the K9 or Pushbot.
|
||||
Look at any Pushbot sample to see how this can be used in an OpMode.
|
||||
Teams can copy one of these to their team folder to create their own robot definition.
|
||||
|
||||
Pushbot: This is a Sample OpMode that uses the Pushbot robot hardware as a base.
|
||||
It may be used to provide some standard baseline Pushbot OpModes, or
|
||||
to demonstrate how a particular sensor or concept can be used directly on the
|
||||
Pushbot chassis.
|
||||
Robot: This is a Sample OpMode that assumes a simple two-motor (differential) drive base.
|
||||
It may be used to provide a common baseline driving OpMode, or
|
||||
to demonstrate how a particular sensor or concept can be used to navigate.
|
||||
|
||||
Concept: This is a sample OpMode that illustrates performing a specific function or concept.
|
||||
These may be complex, but their operation should be explained clearly in the comments,
|
||||
@ -50,8 +44,7 @@ Library: This is a class, or set of classes used to implement some strategy.
|
||||
After the prefix, other conventions will apply:
|
||||
|
||||
* Sensor class names are constructed as: Sensor - Company - Type
|
||||
* Hardware class names are constructed as: Hardware - Robot type
|
||||
* Pushbot class names are constructed as: Pushbot - Mode - Action - OpModetype
|
||||
* Robot class names are constructed as: Robot - Mode - Action - OpModetype
|
||||
* Concept class names are constructed as: Concept - Topic - OpModetype
|
||||
* Library class names are constructed as: Library - Topic - OpModetype
|
||||
|
||||
|
@ -18,14 +18,14 @@ Sensor: This is a Sample OpMode that shows how to use a specific sensor.
|
||||
required to read and display the sensor values.
|
||||
|
||||
Hardware: This is not an actual OpMode, but a helper class that is used to describe
|
||||
one particular robot's hardware configuration: eg: For the K9 or Pushbot.
|
||||
Look at any Pushbot sample to see how this can be used in an OpMode.
|
||||
one particular robot's hardware configuration: eg: For the K9 or Robot.
|
||||
Look at any Robot sample to see how this can be used in an OpMode.
|
||||
Teams can copy one of these to create their own robot definition.
|
||||
|
||||
Pushbot: This is a Sample OpMode that uses the Pushbot robot hardware as a base.
|
||||
It may be used to provide some standard baseline Pushbot opmodes, or
|
||||
Robot: This is a Sample OpMode that uses the Robot robot hardware as a base.
|
||||
It may be used to provide some standard baseline Robot opmodes, or
|
||||
to demonstrate how a particular sensor or concept can be used directly on the
|
||||
Pushbot chassis.
|
||||
Robot chassis.
|
||||
|
||||
Concept: This is a sample OpMode that illustrates performing a specific function or concept.
|
||||
These may be complex, but their operation should be explained clearly in the comments,
|
||||
@ -41,7 +41,7 @@ After the prefix, other conventions will apply:
|
||||
|
||||
* Sensor class names should constructed as: Sensor - Company - Type
|
||||
* Hardware class names should be constructed as: Hardware - Robot type
|
||||
* Pushbot class names should be constructed as: Pushbot - Mode - Action - OpModetype
|
||||
* Robot class names should be constructed as: Robot - Mode - Action - OpModetype
|
||||
* Concept class names should be constructed as: Concept - Topic - OpModetype
|
||||
* Library class names should be constructed as: Library - Topic - OpModetype
|
||||
|
||||
|
@ -37,7 +37,6 @@ https://developer.android.com/guide/topics/connectivity/usb/host
|
||||
|
||||
<!-- see also RobotUsbDevice.getUsbIdentifiers() -->
|
||||
<resources>
|
||||
<usb-device vendor-id="1027" product-id="24577" /> <!-- FT232 Modern Robotics: 0x0403/0x6001 -->
|
||||
<usb-device vendor-id="1027" product-id="24597" /> <!-- FT232 Lynx: 0x0403/0x6015 -->
|
||||
|
||||
<!-- cameras -->
|
||||
|
Reference in New Issue
Block a user