This commit is contained in:
Zelina974 2024-04-06 11:58:16 +02:00
commit 95cb879f7b

View file

@ -77,6 +77,19 @@ public class FTC2024WeRobotControl {
Parent.rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
public void boxElv() {
Parent.lmelevator.setVelocity(600);
Parent.rmelevator.setVelocity(600);
Parent.lmelevator.setTargetPosition(90);
Parent.rmelevator.setTargetPosition(90);
Parent.rotation.setVelocity(600);
Parent.rotation.setTargetPosition(-50);
Parent.lmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
Parent.rmelevator.setMode(DcMotor.RunMode.RUN_TO_POSITION);
Parent.rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
public void posBasse(){
Parent.lmelevator.setVelocity(600);
Parent.rmelevator.setVelocity(600);
@ -89,6 +102,12 @@ public class FTC2024WeRobotControl {
Parent.rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
/*
* return a metre/sec speed
*
* @param motor_speed = (optional) double between 0 and 1; motor power; default
* to 1
*/
public double getSpeedFromMotorSpeed(double motor_speed) {
double speed_tour_par_minutes = this.tour_par_minutes * motor_speed;
@ -97,7 +116,6 @@ public class FTC2024WeRobotControl {
}
/*
* return the needed time for a distance
*
@ -131,6 +149,12 @@ public class FTC2024WeRobotControl {
Parent.rm.setPower(0);
}
/*
* go forward
* when only one argument passed:
*
* @param n_tiles number of tiles
*/
public void forward(double n_tiles) {
this.forward(n_tiles, this.defaultspeed);
}
@ -161,6 +185,7 @@ public class FTC2024WeRobotControl {
public void harvest(double motor_speed) {
Parent.harvestmotor.setPower(motor_speed);
}
public void harvest() {
this.harvest(1.0);
}
@ -184,7 +209,8 @@ public class FTC2024WeRobotControl {
if (Math.abs(angle) == 180) {
angle = (double) (((double) Math.signum(angle)) * 179.9);
}
while(Parent.opModeIsActive() && (Math.abs(robotOrientation.getYaw(AngleUnit.DEGREES) - start_yaw) < Math.abs(angle))){
while (Parent.opModeIsActive()
&& (Math.abs(robotOrientation.getYaw(AngleUnit.DEGREES) - start_yaw) < Math.abs(angle))) {
robotOrientation = Parent.imu.getRobotYawPitchRollAngles();
double yaw = robotOrientation.getYaw(AngleUnit.DEGREES);
Parent.telemetry.addData("Yaw", yaw);
@ -196,11 +222,9 @@ public class FTC2024WeRobotControl {
Parent.lm.setPower(0);
Parent.rm.setPower(0);
}
public void rotate(double angle) {
this.rotate(angle, this.defaultspeed);
}
public void test_forward_10_and_rotate_20deg(){
}
}