Compare commits
3 Commits
0ab402af0f
...
c9ffd4f061
Author | SHA1 | Date | |
---|---|---|---|
c9ffd4f061 | |||
021dfa7222 | |||
233b177cf6 |
@ -1,64 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
import com.acmerobotics.roadrunner.SleepAction;
|
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
|
||||||
import org.firstinspires.ftc.teamcode.subsystem.AutoLine1;
|
|
||||||
import org.firstinspires.ftc.teamcode.subsystem.AutoLine2;
|
|
||||||
import org.firstinspires.ftc.teamcode.subsystem.AutoLine3;
|
|
||||||
|
|
||||||
@Autonomous(name = "BlueNetAuto", group = "Dev")
|
|
||||||
public class NetAuto extends OpMode {
|
|
||||||
|
|
||||||
public Follower follower;
|
|
||||||
|
|
||||||
public AutoLine1 myFirstPath = new AutoLine1();
|
|
||||||
public AutoLine2 mySecondPath = new AutoLine2();
|
|
||||||
public int pathState = 0;
|
|
||||||
@Override
|
|
||||||
public void init() {
|
|
||||||
follower = new Follower(hardwareMap);
|
|
||||||
follower.setMaxPower(0.65);
|
|
||||||
myFirstPath.moveToAutoLine1(follower);
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void loop() {
|
|
||||||
follower.update();
|
|
||||||
switch(pathState) {
|
|
||||||
case 0:
|
|
||||||
if (!follower.isBusy()) {
|
|
||||||
pathState = 1;
|
|
||||||
mySecondPath.moveToAutoLine2(follower);
|
|
||||||
}
|
|
||||||
case 1:
|
|
||||||
if (!follower.isBusy()) {
|
|
||||||
System.out.println("Finished");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// switch(pathState) {
|
|
||||||
// case 0:
|
|
||||||
// if (!follower.isBusy()) {
|
|
||||||
// mySecondPath.moveToAutoLine2(follower);
|
|
||||||
// pathState = 1;
|
|
||||||
// }
|
|
||||||
// case 1:
|
|
||||||
// if (!follower.isBusy()) {
|
|
||||||
// pathState = 2;
|
|
||||||
// }
|
|
||||||
// case 2:
|
|
||||||
// // set path 3
|
|
||||||
// // as if busy, if not, set path 4 and so on.
|
|
||||||
// System.out.print("we're at the end");
|
|
||||||
//
|
|
||||||
// }
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
follower.telemetryDebug(telemetry);
|
|
||||||
}
|
|
||||||
}
|
|
@ -49,7 +49,8 @@ public class PedroConstants {
|
|||||||
public static final double BACK_ENCODER_DIRECTION = Encoder.FORWARD;
|
public static final double BACK_ENCODER_DIRECTION = Encoder.FORWARD;
|
||||||
|
|
||||||
// Arm config
|
// Arm config
|
||||||
public static final String SLIDE_MOTOR = "SlideMotor";
|
public static final String LIFT_SLIDE_LEFT_MOTOR = "lift-slide-left";
|
||||||
|
public static final String LIFT_SLIDE_RIGHT_MOTOR = "lift-slide-right";
|
||||||
public static final String Claw_Servo = "ClawServo";
|
public static final String Claw_Servo = "ClawServo";
|
||||||
public static final String Wrist_Servo = "WristServo";
|
public static final String Wrist_Servo = "WristServo";
|
||||||
public static final String Arm_Servo = "ArmServo";
|
public static final String Arm_Servo = "ArmServo";
|
||||||
|
@ -1,44 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.subsystem;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathBuilder;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
AutoLine# - This file does something of a path......
|
|
||||||
|
|
||||||
*/
|
|
||||||
public class AutoLine1 {
|
|
||||||
|
|
||||||
private PathChain pathChain;
|
|
||||||
private Pose autoLin1StartPose = new Pose(8,65);
|
|
||||||
|
|
||||||
public void moveToAutoLine1(Follower robot) {
|
|
||||||
PathBuilder builder = new PathBuilder();
|
|
||||||
builder
|
|
||||||
.addPath(
|
|
||||||
// Line 1
|
|
||||||
new BezierLine(
|
|
||||||
new Point(8.000, 65.000, Point.CARTESIAN),
|
|
||||||
new Point(30.000, 72.000, Point.CARTESIAN)
|
|
||||||
)
|
|
||||||
)
|
|
||||||
.setConstantHeadingInterpolation(Math.toRadians(0));
|
|
||||||
pathChain = builder.build();
|
|
||||||
robot.setStartingPose(autoLin1StartPose);
|
|
||||||
robot.followPath(pathChain);
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
@ -1,40 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.subsystem;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathBuilder;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
AutoLine# - This file does something of a path......
|
|
||||||
|
|
||||||
*/
|
|
||||||
public class AutoLine2 {
|
|
||||||
private PathChain pathChain;
|
|
||||||
public void moveToAutoLine2(Follower robot) {
|
|
||||||
PathBuilder builder = new PathBuilder();
|
|
||||||
builder
|
|
||||||
.addPath(
|
|
||||||
// Line 2
|
|
||||||
new BezierCurve(
|
|
||||||
new Point(36.000, 72.000, Point.CARTESIAN),
|
|
||||||
new Point(24.000, 24.000, Point.CARTESIAN),
|
|
||||||
new Point(72.000, 36.000, Point.CARTESIAN),
|
|
||||||
new Point(56.000, 24.000, Point.CARTESIAN)
|
|
||||||
)
|
|
||||||
)
|
|
||||||
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(180));
|
|
||||||
pathChain = builder.build();
|
|
||||||
robot.followPath(pathChain);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
@ -1,73 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode.subsystem;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
|
||||||
import com.acmerobotics.roadrunner.Action;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathBuilder;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
|
|
||||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
AutoLine# - This file does something of a path......
|
|
||||||
|
|
||||||
*/
|
|
||||||
public class AutoLine3 implements Action {
|
|
||||||
|
|
||||||
private Follower actionRobot;
|
|
||||||
private PathChain pathChain;
|
|
||||||
|
|
||||||
private Pose startPose = new Pose(56,24);
|
|
||||||
|
|
||||||
public AutoLine3(Follower robot) {
|
|
||||||
this.actionRobot = robot;
|
|
||||||
this.actionRobot.setStartingPose(startPose);
|
|
||||||
|
|
||||||
PathBuilder builder = new PathBuilder();
|
|
||||||
builder
|
|
||||||
/* .addPath(
|
|
||||||
// Line 1
|
|
||||||
new BezierLine(
|
|
||||||
new Point(8.000, 65.000, Point.CARTESIAN),
|
|
||||||
new Point(30.000, 72.000, Point.CARTESIAN)
|
|
||||||
// This is the origional new Point(36.000, 72.000, Point.CARTESIAN)
|
|
||||||
)
|
|
||||||
)
|
|
||||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
|
||||||
.addPath(
|
|
||||||
// Line 2
|
|
||||||
new BezierCurve(
|
|
||||||
new Point(36.000, 72.000, Point.CARTESIAN),
|
|
||||||
new Point(24.000, 24.000, Point.CARTESIAN),
|
|
||||||
new Point(72.000, 36.000, Point.CARTESIAN),
|
|
||||||
new Point(56.000, 24.000, Point.CARTESIAN)
|
|
||||||
)
|
|
||||||
)
|
|
||||||
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(180)) */
|
|
||||||
.addPath(
|
|
||||||
// Line 3
|
|
||||||
new BezierLine(
|
|
||||||
new Point(56.000, 24.000, Point.CARTESIAN),
|
|
||||||
new Point(18.000, 24.000, Point.CARTESIAN)
|
|
||||||
)
|
|
||||||
)
|
|
||||||
.setTangentHeadingInterpolation();
|
|
||||||
|
|
||||||
pathChain = builder.build();
|
|
||||||
|
|
||||||
this.actionRobot.followPath(this.pathChain);
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
|
||||||
this.actionRobot.update();
|
|
||||||
return this.actionRobot.isBusy();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
@ -0,0 +1,72 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.subsystem;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_LEFT_MOTOR;
|
||||||
|
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_RIGHT_MOTOR;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
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.DcMotorEx;
|
||||||
|
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||||
|
|
||||||
|
|
||||||
|
@Config
|
||||||
|
@Autonomous(name = "Lift Motor Subsystem - PID Test")
|
||||||
|
public class LiftMotorSubsystem extends LinearOpMode {
|
||||||
|
|
||||||
|
private DcMotorEx liftSlideLeft;
|
||||||
|
private DcMotorEx liftSlideRight;
|
||||||
|
public static double kp = 0.0015, ki = 0, kd = 0;
|
||||||
|
private double lastError = 0;
|
||||||
|
private double integralSum = 0;
|
||||||
|
public static int targetPosition = 0;
|
||||||
|
private final FtcDashboard dashboard = FtcDashboard.getInstance();
|
||||||
|
private ElapsedTime timer = new ElapsedTime();
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
TelemetryPacket packet = new TelemetryPacket();
|
||||||
|
dashboard.setTelemetryTransmissionInterval(25);
|
||||||
|
|
||||||
|
liftSlideLeft = hardwareMap.get(DcMotorEx.class, LIFT_SLIDE_LEFT_MOTOR);
|
||||||
|
liftSlideRight = hardwareMap.get(DcMotorEx.class, LIFT_SLIDE_RIGHT_MOTOR);
|
||||||
|
|
||||||
|
liftSlideLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
|
liftSlideLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
liftSlideLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
|
||||||
|
liftSlideRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
|
liftSlideRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
liftSlideRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||||
|
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
while(opModeIsActive()) {
|
||||||
|
double power = calculatePower(targetPosition, liftSlideLeft.getCurrentPosition());
|
||||||
|
|
||||||
|
packet.put("Power", power);
|
||||||
|
packet.put("Position", liftSlideLeft.getCurrentPosition());
|
||||||
|
packet.put("Error", lastError);
|
||||||
|
packet.put("Seconds", timer.seconds());
|
||||||
|
|
||||||
|
liftSlideLeft.setPower(power);
|
||||||
|
liftSlideRight.setPower(power);
|
||||||
|
|
||||||
|
dashboard.sendTelemetryPacket(packet);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private double calculatePower(int targetPosition, int currentPosition) {
|
||||||
|
// reference is targetPosition, state is currentPosition
|
||||||
|
double error = targetPosition - currentPosition;
|
||||||
|
integralSum += error * timer.seconds();
|
||||||
|
double derivative = (error - lastError) / timer.seconds();
|
||||||
|
lastError = error;
|
||||||
|
timer.reset();
|
||||||
|
return (error * kp) + (derivative * kd) + (integralSum * ki);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
Reference in New Issue
Block a user