Add TODO comments
This commit is contained in:
@ -34,6 +34,7 @@ import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
||||
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.IMU;
|
||||
import com.qualcomm.robotcore.hardware.VoltageSensor;
|
||||
@ -53,6 +54,8 @@ import java.util.List;
|
||||
public final class MecanumDrive {
|
||||
public static class Params {
|
||||
// IMU orientation
|
||||
// TODO: fill in these values based on
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
|
||||
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
|
||||
RevHubOrientationOnRobot.LogoFacingDirection.UP;
|
||||
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
|
||||
@ -136,6 +139,9 @@ public final class MecanumDrive {
|
||||
lastRightFrontPos = rightFront.getPositionAndVelocity().position;
|
||||
|
||||
lastHeading = Rotation2d.exp(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS));
|
||||
|
||||
// TODO: reverse encoders if needed
|
||||
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
}
|
||||
|
||||
@Override
|
||||
@ -193,6 +199,8 @@ public final class MecanumDrive {
|
||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||
}
|
||||
|
||||
// TODO: make sure your config has motors with these names (or change them)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
|
||||
leftBack = hardwareMap.get(DcMotorEx.class, "leftBack");
|
||||
rightBack = hardwareMap.get(DcMotorEx.class, "rightBack");
|
||||
@ -203,6 +211,11 @@ public final class MecanumDrive {
|
||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
// TODO: reverse motor directions if needed
|
||||
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
imu = hardwareMap.get(IMU.class, "imu");
|
||||
IMU.Parameters parameters = new IMU.Parameters(new RevHubOrientationOnRobot(
|
||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||
|
@ -40,12 +40,12 @@ import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
||||
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.IMU;
|
||||
import com.qualcomm.robotcore.hardware.VoltageSensor;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.messages.DriveCommandMessage;
|
||||
import org.firstinspires.ftc.teamcode.messages.MecanumEncodersMessage;
|
||||
import org.firstinspires.ftc.teamcode.messages.PoseMessage;
|
||||
import org.firstinspires.ftc.teamcode.messages.TankCommandMessage;
|
||||
import org.firstinspires.ftc.teamcode.messages.TankEncodersMessage;
|
||||
@ -60,6 +60,8 @@ import java.util.List;
|
||||
public final class TankDrive {
|
||||
public static class Params {
|
||||
// IMU orientation
|
||||
// TODO: fill in these values based on
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
|
||||
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
|
||||
RevHubOrientationOnRobot.LogoFacingDirection.UP;
|
||||
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
|
||||
@ -150,6 +152,9 @@ public final class TankDrive {
|
||||
lastRightPos /= rightEncs.size();
|
||||
this.rightEncs = Collections.unmodifiableList(rightEncs);
|
||||
}
|
||||
|
||||
// TODO: reverse encoder directions if needed
|
||||
// leftEncs.get(0).setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
}
|
||||
|
||||
@Override
|
||||
@ -205,6 +210,9 @@ public final class TankDrive {
|
||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||
}
|
||||
|
||||
// TODO: make sure your config has motors with these names (or change them)
|
||||
// add additional motors on each side if you have them
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
leftMotors = Arrays.asList(hardwareMap.get(DcMotorEx.class, "left"));
|
||||
rightMotors = Arrays.asList(hardwareMap.get(DcMotorEx.class, "right"));
|
||||
|
||||
@ -215,6 +223,11 @@ public final class TankDrive {
|
||||
m.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
}
|
||||
|
||||
// TODO: reverse motor directions if needed
|
||||
// leftMotors.get(0).setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
imu = hardwareMap.get(IMU.class, "imu");
|
||||
IMU.Parameters parameters = new IMU.Parameters(new RevHubOrientationOnRobot(
|
||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||
|
@ -30,6 +30,9 @@ public final class ThreeDeadWheelLocalizer implements Localizer {
|
||||
private int lastPar0Pos, lastPar1Pos, lastPerpPos;
|
||||
|
||||
public ThreeDeadWheelLocalizer(HardwareMap hardwareMap, double inPerTick) {
|
||||
// TODO: make sure your config has **motors** with these names (or change them)
|
||||
// the encoders should be plugged into the slot matching the named motor
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
par0 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par0")));
|
||||
par1 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par1")));
|
||||
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));
|
||||
|
@ -37,6 +37,9 @@ public final class TwoDeadWheelLocalizer implements Localizer {
|
||||
private double lastRawHeadingVel, headingVelOffset;
|
||||
|
||||
public TwoDeadWheelLocalizer(HardwareMap hardwareMap, IMU imu, double inPerTick) {
|
||||
// TODO: make sure your config has **motors** with these names (or change them)
|
||||
// the encoders should be plugged into the slot matching the named motor
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
par = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par")));
|
||||
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));
|
||||
this.imu = imu;
|
||||
|
@ -31,6 +31,7 @@ import java.util.Arrays;
|
||||
import java.util.List;
|
||||
|
||||
public final class TuningOpModes {
|
||||
// TODO: change this to TankDrive.class if you're using tank
|
||||
public static final Class<?> DRIVE_CLASS = MecanumDrive.class;
|
||||
|
||||
public static final String GROUP = "quickstart";
|
||||
|
Reference in New Issue
Block a user