power-play/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/PushbotAutoDriveToLine_Linear.java
2020-09-22 19:37:25 -07:00

119 lines
5.5 KiB
Java

/* 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);
}
}