Extract motor direction to constants so they are set in one place
This commit is contained in:
@ -10,6 +10,10 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstan
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryDrivePIDFFeedForward;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryHeadingPIDFFeedForward;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryTranslationalPIDFFeedForward;
|
||||
@ -23,7 +27,6 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
|
||||
|
||||
@ -166,10 +169,10 @@ public class Follower {
|
||||
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);
|
||||
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);
|
||||
|
||||
// TODO: Make sure that this is the direction your motors need to be reversed in.
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftRear.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftFront.setDirection(leftFrontMotorDirection);
|
||||
leftRear.setDirection(leftRearMotorDirection);
|
||||
rightFront.setDirection(rightFrontMotorDirection);
|
||||
rightRear.setDirection(rightRearMotorDirection);
|
||||
|
||||
motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear);
|
||||
|
||||
|
@ -4,6 +4,10 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstan
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorDirection;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@ -12,7 +16,6 @@ import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
@ -57,9 +60,10 @@ public class LocalizationTest extends OpMode {
|
||||
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);
|
||||
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);
|
||||
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftRear.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftFront.setDirection(leftFrontMotorDirection);
|
||||
leftRear.setDirection(leftRearMotorDirection);
|
||||
rightFront.setDirection(rightFrontMotorDirection);
|
||||
rightRear.setDirection(rightRearMotorDirection);
|
||||
|
||||
motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear);
|
||||
|
||||
|
@ -1,6 +1,7 @@
|
||||
package org.firstinspires.ftc.teamcode.pedroPathing.tuning;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
|
||||
@ -28,6 +29,11 @@ public class FollowerConstants {
|
||||
public static String rightFrontMotorName = "rightFront";
|
||||
public static String rightRearMotorName = "rightRear";
|
||||
|
||||
public static DcMotorSimple.Direction leftFrontMotorDirection = DcMotorSimple.Direction.REVERSE;
|
||||
public static DcMotorSimple.Direction rightFrontMotorDirection = DcMotorSimple.Direction.REVERSE;
|
||||
public static DcMotorSimple.Direction leftRearMotorDirection = DcMotorSimple.Direction.FORWARD;
|
||||
public static DcMotorSimple.Direction rightRearMotorDirection = DcMotorSimple.Direction.FORWARD;
|
||||
|
||||
// This section is for setting the actual drive vector for the front left wheel, if the robot
|
||||
// is facing a heading of 0 radians with the wheel centered at (0,0)
|
||||
private static double xMovement = 81.34056;
|
||||
|
@ -4,6 +4,10 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstan
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorDirection;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@ -12,7 +16,6 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
@ -71,10 +74,10 @@ public class ForwardVelocityTuner extends OpMode {
|
||||
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);
|
||||
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);
|
||||
|
||||
// TODO: Make sure that this is the direction your motors need to be reversed in.
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftRear.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftFront.setDirection(leftFrontMotorDirection);
|
||||
leftRear.setDirection(leftRearMotorDirection);
|
||||
rightFront.setDirection(rightFrontMotorDirection);
|
||||
rightRear.setDirection(rightRearMotorDirection);
|
||||
|
||||
motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear);
|
||||
|
||||
|
@ -4,6 +4,10 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstan
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorDirection;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@ -12,7 +16,6 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
@ -74,10 +77,10 @@ public class ForwardZeroPowerAccelerationTuner extends OpMode {
|
||||
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);
|
||||
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);
|
||||
|
||||
// TODO: Make sure that this is the direction your motors need to be reversed in.
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftRear.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftFront.setDirection(leftFrontMotorDirection);
|
||||
leftRear.setDirection(leftRearMotorDirection);
|
||||
rightFront.setDirection(rightFrontMotorDirection);
|
||||
rightRear.setDirection(rightRearMotorDirection);
|
||||
|
||||
motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear);
|
||||
|
||||
|
@ -4,6 +4,10 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstan
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorDirection;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@ -12,7 +16,6 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
@ -74,10 +77,10 @@ public class LateralZeroPowerAccelerationTuner extends OpMode {
|
||||
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);
|
||||
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);
|
||||
|
||||
// TODO: Make sure that this is the direction your motors need to be reversed in.
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftRear.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftFront.setDirection(leftFrontMotorDirection);
|
||||
leftRear.setDirection(leftRearMotorDirection);
|
||||
rightFront.setDirection(rightFrontMotorDirection);
|
||||
rightRear.setDirection(rightRearMotorDirection);
|
||||
|
||||
motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear);
|
||||
|
||||
|
@ -4,6 +4,10 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstan
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorDirection;
|
||||
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorDirection;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@ -12,7 +16,6 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
@ -71,10 +74,10 @@ public class StrafeVelocityTuner extends OpMode {
|
||||
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);
|
||||
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);
|
||||
|
||||
// TODO: Make sure that this is the direction your motors need to be reversed in.
|
||||
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftRear.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
leftFront.setDirection(leftFrontMotorDirection);
|
||||
leftRear.setDirection(leftRearMotorDirection);
|
||||
rightFront.setDirection(rightFrontMotorDirection);
|
||||
rightRear.setDirection(rightRearMotorDirection);
|
||||
|
||||
motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear);
|
||||
|
||||
|
Reference in New Issue
Block a user