Skip to content

Commit

Permalink
Merge branch 'master' into implementingSensorsandAutoPaths
Browse files Browse the repository at this point in the history
  • Loading branch information
alan412 authored Jan 19, 2024
2 parents ee8c93b + 479a112 commit af9660b
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 23 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package org.firstinspires.ftc.teamcode.ftc16072.Mechanisms;

import com.acmerobotics.dashboard.config.Config;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap;

Expand All @@ -9,17 +10,27 @@
import java.util.Arrays;
import java.util.List;

@Config
public class Climber implements Mechanism{
private DcMotor climberMotor;
public static double ClimbSpeed = 1;
@Override
public void init(HardwareMap hwMap) {
climberMotor = hwMap.get(DcMotor.class,"climber_motor");
}

@Override
public List<QQtest> getTests() {
return Arrays.asList(
new TestMotor("climber_motor",0.5,climberMotor)
);
new TestMotor("climber_motor",0.5,climberMotor));

}
public void Climb() {
climberMotor.setPower(ClimbSpeed);
}




}



Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,11 @@

@TeleOp()
public class OutreachDriveOnly extends QQOpMode {
public static double OUTREACH_SPEED = .2;
public static final double OUTREACH_SPEED = .5;
public static final double OUTREACH_TURBO_SPEED = .75;
public static final double MAX_SPEED = 1.0;
public static final double TRIGGER_THRESHOLD = 0.2;


@Override
public void init() {
robot.makeDriveOnly();
Expand All @@ -19,22 +18,16 @@ public void init() {
@Override
public void loop() {
double speed_multiplier = OUTREACH_SPEED;
if (gamepad1.right_trigger > TRIGGER_THRESHOLD) {
if(gamepad1.right_trigger > TRIGGER_THRESHOLD){
speed_multiplier = OUTREACH_TURBO_SPEED;

}
if (gamepad1.right_bumper && gamepad1.left_bumper) {
speed_multiplier = MAX_SPEED;
if(gamepad1.right_bumper && gamepad1.left_bumper){
speed_multiplier = MAX_SPEED;
}
}
if (gamepad2.a) {
robot.nav.fieldRelative(speed_multiplier * 0, speed_multiplier * 0, speed_multiplier * 0);
} else {


robot.nav.fieldRelative(speed_multiplier * -gamepad1.left_stick_y,
speed_multiplier * gamepad1.left_stick_x,
speed_multiplier * gamepad1.right_stick_x);
}
robot.nav.fieldRelative(speed_multiplier * -gamepad1.left_stick_y,
speed_multiplier * gamepad1.left_stick_x,
speed_multiplier * gamepad1.right_stick_x);
}
}
//Left Bumper for Turbo
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

import org.firstinspires.ftc.teamcode.ftc16072.Mechanisms.Arm;
import org.firstinspires.ftc.teamcode.ftc16072.Mechanisms.Camera;
import org.firstinspires.ftc.teamcode.ftc16072.Mechanisms.Climber;
import org.firstinspires.ftc.teamcode.ftc16072.Mechanisms.ControlHub;
import org.firstinspires.ftc.teamcode.ftc16072.Mechanisms.HoldingCell;
import org.firstinspires.ftc.teamcode.ftc16072.Mechanisms.Lift;
Expand Down Expand Up @@ -32,6 +33,7 @@ public class Robot {
public Lift lift;
public Arm arm;
public Placement placement;
public Climber climber;



Expand All @@ -47,19 +49,21 @@ public Robot() {
lift = new Lift();
arm = new Arm();
placement = new Placement();
climber = new Climber();


mechanisms = Arrays.asList(
mecanumDrive,
controlHub,
//intake,
intake,
cameraBack,
cameraFront,
// holdingCell,
holdingCell,
lift,
arm,
placement
// lineDetector
placement,
lineDetector,
climber
);
}

Expand Down

0 comments on commit af9660b

Please sign in to comment.