Skip to content

Commit

Permalink
Merge pull request #1 from Thierry-Lachance/main
Browse files Browse the repository at this point in the history
added function file for arm/elevator/drivetrain
  • Loading branch information
Thierry-Lachance authored Oct 24, 2024
2 parents 80de38f + 2c83158 commit 3adae42
Show file tree
Hide file tree
Showing 11 changed files with 175 additions and 135 deletions.
1 change: 0 additions & 1 deletion .idea/misc.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

34 changes: 28 additions & 6 deletions .idea/workspace.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

5 changes: 5 additions & 0 deletions TeamCode/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,13 @@
// Include common definitions from above.
apply from: '../build.common.gradle'
apply from: '../build.dependencies.gradle'
apply plugin: 'org.jetbrains.kotlin.android'

android {
namespace = 'org.firstinspires.ftc.teamcode'
kotlinOptions {
jvmTarget = '1.8'
}

packagingOptions {
jniLibs.useLegacyPackaging true
Expand All @@ -25,4 +29,5 @@ android {

dependencies {
implementation project(':FtcRobotController')
implementation 'androidx.core:core-ktx:1.13.1'
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
package org.firstinspires.ftc.teamcode

import com.qualcomm.robotcore.hardware.AnalogInput

class ArmFunction {
companion object {
@JvmStatic
fun moveArm(power: Double, armSensor: AnalogInput): Double {
return if (power >= 0 && armSensor.voltage < 0.75) power
else if (power >= 0 && armSensor.voltage > 2.55) power
else 0.0
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package org.firstinspires.ftc.teamcode

import kotlin.math.abs

class DrivetrainFunction {

companion object {
@JvmStatic
fun calculateTicks(Cm: Double): Double {

val COUNTS_PER_MOTOR_REV = 536.6

val WHEEL_DIAMETER_CM = 10.0

val COUNTS_PER_Cm = COUNTS_PER_MOTOR_REV / (WHEEL_DIAMETER_CM * 3.1415)
return COUNTS_PER_Cm * Cm
}

@JvmStatic
fun calculatePower(targetPos: Double, currentPos: Double): Double {
return if (abs(targetPos - currentPos) > 50) {
if (abs(currentPos - targetPos) < 100) 0.25
else if (abs(currentPos - targetPos) < 500) 0.50
else if (abs(currentPos - targetPos) < 1000) 0.75
else 1.0
} else 0.0

}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package org.firstinspires.ftc.teamcode

import com.qualcomm.robotcore.hardware.DigitalChannel

class ElevatorFunction {
companion object {
@JvmStatic
fun moveElevator(
power: Double,
elevatorIn: DigitalChannel,
elevatorOut: DigitalChannel
): Double {
return if (elevatorIn.state && power >= 0) power
else if (elevatorOut.state && power >= 0) power
else 0.0
}
}
}
54 changes: 9 additions & 45 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TeleOp.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,6 @@
@com.qualcomm.robotcore.eventloop.opmode.TeleOp
public class TeleOp extends LinearOpMode {

double flEncoderPos;
double frEncoderPos;
double blEncoderPos;
double brEncoderPos;

double armOutPos;
double armInPos;
double elevatorInPos;
Expand All @@ -25,6 +20,7 @@ public class TeleOp extends LinearOpMode {

Servo servo1;
Servo servo2;

@Override
public void runOpMode() throws InterruptedException {

Expand All @@ -40,11 +36,6 @@ public void runOpMode() throws InterruptedException {
DigitalChannel elevatorOut = hardwareMap.digitalChannel.get("elevatorOut");
AnalogInput armSensor = hardwareMap.analogInput.get("armSensor");

double flEncoder = frontLeftMotor.getCurrentPosition();
double frEncoder = frontRightMotor.getCurrentPosition();
double blEncoder = backLeftMotor.getCurrentPosition();
double brEncoder = backRightMotor.getCurrentPosition();

frontRightMotor.setDirection(DcMotorSimple.Direction.REVERSE);
backRightMotor.setDirection(DcMotorSimple.Direction.REVERSE);

Expand All @@ -65,11 +56,6 @@ public void runOpMode() throws InterruptedException {
armMotor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
elevatorMotor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);

flEncoderPos = flEncoder;
frEncoderPos = frEncoder;
blEncoderPos = blEncoder;
brEncoderPos = brEncoder;

elevatorInPos = elevatorMotor.getCurrentPosition();
armInPos = armMotor.getCurrentPosition();

Expand All @@ -90,50 +76,28 @@ public void runOpMode() throws InterruptedException {
double backLeftPower = (y - x + rx) / denominator;
double frontRightPower = (y - x - rx) / denominator;
double backRightPower = (y + x - rx) / denominator;
if(gamepad1.x){
if (gamepad1.x) {
servo1.setPosition(0.25);
servo2.setPosition(0.75);
}
if(gamepad1.y){
if (gamepad1.y) {
servo1.setPosition(0.75);
servo2.setPosition(0.25);
}
if(gamepad1.a){
moveElevator(1.0, elevatorMotor, elevatorIn, elevatorOut);
}
if(gamepad1.b){
moveElevator(-1.0, elevatorMotor, elevatorIn, elevatorOut);
}
if (gamepad1.a) elevatorMotor.setPower(ElevatorFunction.moveElevator(1.0, elevatorIn, elevatorOut));

if (gamepad1.b) elevatorMotor.setPower(ElevatorFunction.moveElevator(-1.0, elevatorIn, elevatorOut));

if (gamepad1.left_bumper) armMotor.setPower(ArmFunction.moveArm(1.0, armSensor));

if (gamepad1.right_bumper) armMotor.setPower(ArmFunction.moveArm(-1.0, armSensor));

frontLeftMotor.setPower(frontLeftPower);
backLeftMotor.setPower(backLeftPower);
frontRightMotor.setPower(frontRightPower);
backRightMotor.setPower(backRightPower);
}
}
public void moveArm(double power, DcMotor armMotor, AnalogInput armSensor){
if(power >= 0 && armSensor.getVoltage() < 0.75){
armMotor.setPower(power);
}
if(power >= 0 && armSensor.getVoltage() > 2.55){
armMotor.setPower(power);
}
else{
armMotor.setPower(0.0);
}

}
public void moveElevator(double power, DcMotor elevatorMotor, DigitalChannel elevatorIn, DigitalChannel elevatorOut){
if(elevatorIn.getState() && power >= 0){
elevatorMotor.setPower(power);
}
if(elevatorOut.getState() && power >= 0){
elevatorMotor.setPower(power);
}
else{
elevatorMotor.setPower(0.0);
}

}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;


@Autonomous
public class autoTemplate extends LinearOpMode {

DcMotor frontLeftMotor;
DcMotor backLeftMotor;
DcMotor frontRightMotor;
DcMotor backRightMotor;

@Override
public void runOpMode() throws InterruptedException {
frontLeftMotor = hardwareMap.dcMotor.get("frontLeft");
backLeftMotor = hardwareMap.dcMotor.get("backLeft");
frontRightMotor = hardwareMap.dcMotor.get("frontRight");
backRightMotor = hardwareMap.dcMotor.get("backRight");


frontRightMotor.setDirection(DcMotorSimple.Direction.REVERSE);
backRightMotor.setDirection(DcMotorSimple.Direction.REVERSE);

frontLeftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
frontLeftMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
frontRightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
frontRightMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backLeftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
backLeftMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backRightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
backRightMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

waitForStart();

while (opModeIsActive()) {
double targetFL = DrivetrainFunction.calculateTicks(60.0);
double targetFR = DrivetrainFunction.calculateTicks(60.0);
double targetBL = DrivetrainFunction.calculateTicks(60.0);
double targetBR = DrivetrainFunction.calculateTicks(60.0);
encoderDrive(targetFL, targetFR, targetBL, targetBR);

}
}

public void encoderDrive(double targetFL, double targetFR, double targetBL, double targetBR) {
while (DrivetrainFunction.calculatePower(targetFL, frontLeftMotor.getCurrentPosition()) != 0
&& DrivetrainFunction.calculatePower(targetFR, frontRightMotor.getCurrentPosition()) != 0
&& DrivetrainFunction.calculatePower(targetBL, backLeftMotor.getCurrentPosition()) != 0
&& DrivetrainFunction.calculatePower(targetBR, backRightMotor.getCurrentPosition()) != 0) {
frontLeftMotor.setPower(DrivetrainFunction.calculatePower(targetFL, frontLeftMotor.getCurrentPosition()));
frontRightMotor.setPower(DrivetrainFunction.calculatePower(targetFR, frontRightMotor.getCurrentPosition()));
backLeftMotor.setPower(DrivetrainFunction.calculatePower(targetBL, backLeftMotor.getCurrentPosition()));
backRightMotor.setPower(DrivetrainFunction.calculatePower(targetBR, backRightMotor.getCurrentPosition()));
}


}


}

Original file line number Diff line number Diff line change
@@ -1,13 +1,14 @@
package org.firstinspires.ftc.teamcode;

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.DcMotorSimple;




@Disabled
@Autonomous
public class autoTest extends LinearOpMode {

Expand Down
Loading

0 comments on commit 3adae42

Please sign in to comment.