manual control complete, and states started again

This commit is contained in:
robotics2
2023-11-02 15:58:45 -07:00
parent 089ca0cf3d
commit 387cca2ace
4 changed files with 124 additions and 10 deletions

View File

@ -118,8 +118,7 @@ public class Autonomoustest extends LinearOpMode {
// Wait for the game to start (driver presses PLAY)
waitForStart();
{
//executeAuto();
testGripper();
executeAuto();
}
@ -252,9 +251,7 @@ public class Autonomoustest extends LinearOpMode {
}
public void executeAuto()
{
raisearm(100);
wrist.setPosition(0);
arm.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
driveForward(28);
int blueleft = readColorLeft();
int blueright = readColorRight();
@ -266,7 +263,9 @@ public class Autonomoustest extends LinearOpMode {
turnLeft(90);
straightLeft(2);
driveForward(11);
driveForward(-30);
raisearm(26);
arm.setPower(0);
driveForward(-26);
straightLeft(32);
turnLeft(10);
driveForward(18);
@ -287,8 +286,10 @@ public class Autonomoustest extends LinearOpMode {
//telemetry.addData("color sensor", "right");
if(blueleft < blueright)
telemetry.addData("color sensor","right");
straightRight(11.5);
driveForward(-17);
straightRight(8);
raisearm(30);
arm.setPower(0);
driveForward(-13.5);
turnLeft(90);
straightLeft(15);
driveForward(8);
@ -304,8 +305,10 @@ public class Autonomoustest extends LinearOpMode {
}
else
telemetry.addData("position","center");
driveForward(7);
driveForward(-7);
driveForward(3.5);
raisearm(30);
arm.setPower(0);
driveForward(-3.5);
straightRight(11.5);
driveForward(-17);
turnLeft(90);

View File

@ -24,6 +24,7 @@ public class FullRobotControl extends OpMode {
Servo gripper;
Servo wrist;
DcMotor arm;
DcMotor hang;
DcMotor armThroughBoreEncoder;
public ElapsedTime runtime = new ElapsedTime();
static final double TICKS_TO_DEGREES = 0.07462686567;
@ -73,6 +74,7 @@ public class FullRobotControl extends OpMode {
wrist = hardwareMap.servo.get("wrist");
arm = hardwareMap.dcMotor.get("arm raise");
armThroughBoreEncoder = hardwareMap.dcMotor.get("arm raise");
hang = hardwareMap.dcMotor.get("hang");
wrist.setPosition(1);
}

View File

@ -24,6 +24,7 @@ public class arm extends OpMode {
DcMotor backRight;
DcMotor frontLeft;
DcMotor backLeft;
DcMotor hang;
/**
@ -65,6 +66,7 @@ public class arm extends OpMode {
backRight = hardwareMap.dcMotor.get("Drive back rt");
frontLeft = hardwareMap.dcMotor.get("Drive front lt");
backLeft = hardwareMap.dcMotor.get("Drive back lt");
hang = hardwareMap.dcMotor.get("hang");
@ -122,6 +124,7 @@ public class arm extends OpMode {
}
else
{
arm.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
arm.setPower(0);
}
if(gamepad2.left_trigger > 0.35)
@ -143,6 +146,19 @@ public class arm extends OpMode {
{
wrist.setPosition(0);
}
if (gamepad1.dpad_up)
{
hang.setPower(1);
}
hang.setPower(0);
if (gamepad1.dpad_down)
{
hang.setPower(-.5);
}
else {
hang.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
hang.setPower(0);
}
axial = -gamepad1.left_stick_y/num; // Note: pushing stick forward gives negative value
lateral = gamepad1.left_stick_x/num;
yaw = gamepad1.right_stick_x/(num+0.5);

View File

@ -0,0 +1,93 @@
/* 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.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.ColorSensor;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;
@Autonomous(name="Robot: colorRead", group="Robot")
//@Disabled
public class colorRead extends LinearOpMode {
/* Declare OpMode members. */
private ColorSensor colorRight = null;
private ColorSensor colorLeft = null;
// 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.
@Override
public void runOpMode() {
hardwareinit();
readColorRight();
readColorLeft();
}
//
public int readColorRight() {
telemetry.addData("Clear", colorRight.alpha());
telemetry.addData("Red ", colorRight.red());
telemetry.addData("Green", colorRight.green());
telemetry.addData("Blue ", colorRight.blue());
int bluenumber = colorRight.blue();
return bluenumber;
}
public int readColorLeft() {
telemetry.addData("Clear Left", colorLeft.alpha());
telemetry.addData("Red left ", colorLeft.red());
telemetry.addData("Green left", colorLeft.green());
telemetry.addData("Blue left", colorLeft.blue());
int bluenumber = colorLeft.blue();
return bluenumber;
}
public void hardwareinit() {
colorRight = hardwareMap.get(ColorSensor.class, "color right");
colorLeft = hardwareMap.get(ColorSensor.class, "color left");
}
}