ftc2024-robotcode/ftc2024_autonome_api.java

116 lines
3.1 KiB
Java
Raw Normal View History

2024-03-07 15:15:33 +01:00
package org.firstinspires.ftc.teamcode;
2024-03-07 14:54:46 +01:00
2024-03-10 14:32:50 +01:00
import fr.werobot.ftc2024.robotcontrol.FTC2024WeRobotControl; //a tester car pas sur que ça fonctionne
2024-03-08 15:26:48 +01:00
2024-03-07 15:15:33 +01:00
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.IMU;
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
import com.qualcomm.robotcore.hardware.ImuOrientationOnRobot;
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
import org.firstinspires.ftc.robotcore.external.navigation.Orientation;
import org.firstinspires.ftc.robotcore.external.navigation.AxesOrder;
import org.firstinspires.ftc.robotcore.external.navigation.AxesReference;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
@Autonomous
public class ftc2024_autonome_api extends LinearOpMode {
2024-03-08 15:57:46 +01:00
public String autonomous_mode;
2024-03-08 15:26:48 +01:00
public DcMotor lm;
public DcMotor rm;
public DcMotor harvestmotor;
public IMU imu;
2024-03-07 15:15:33 +01:00
@Override
public void runOpMode() {
2024-03-08 15:26:48 +01:00
lm = hardwareMap.get(DcMotor.class, "blm");
rm = hardwareMap.get(DcMotor.class, "brm");
harvestmotor = hardwareMap.get(DcMotor.class, "flm");
rm.setDirection(DcMotor.Direction.REVERSE);
imu = hardwareMap.get(IMU.class, "imu");
imu.initialize(
new IMU.Parameters(
new RevHubOrientationOnRobot(
RevHubOrientationOnRobot.LogoFacingDirection.UP,
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD
)
)
);
imu.resetYaw();
YawPitchRollAngle robotOrientation;
2024-03-08 15:26:48 +01:00
FTC2024WeRobotControl robot = FTC2024WeRobotControl(this);
waitForStart();
robotOrientation = imu.getYawPitchRollAngles();
if(opModeIsRunning()){
2024-03-08 15:57:46 +01:00
/*
* autonomous_mode differents possibles values respect the next scheme:
* team_color_shortcode + start_line_index + direct_or_no
*
* team_color_shortcode = "b" for blue & "r" for red
* start_line_index = 4 or 2 see competition manual appendix B Tile location plan
* direct_or_no = "d" to direct go to pixel deliver zone or "n" to harvest pixels before to go in deliver zone
*
* default is "b4d"
*/
switch (autonomous_mode){
default:
robot.forward(0.5);
robot.rotate(-90.0);
robot.forward(1.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
break;
case ("b2d"):
robot.forward(0.5);
robot.rotate(-90.0);
robot.forward(2.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
break;
case ("r4d"):
robot.forward(0.5);
robot.rotate(90.0);
robot.forward(1.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
2024-03-08 15:57:46 +01:00
break;
case ("r2d"):
robot.forward(0.5);
robot.rotate(90.0);
robot.forward(2.5);
robot.harvest(-1);
robot.backward(1);
robot.harvest(0);
2024-03-08 15:57:46 +01:00
break;
case ("b4n"):
break;
case ("b2n"):
break;
case ("r4n"):
break;
case ("r2n"):
break;
}
2024-03-08 15:26:48 +01:00
}
2024-03-07 15:15:33 +01:00
}
}