Skip to content

Commit

Permalink
Add TODO comments
Browse files Browse the repository at this point in the history
  • Loading branch information
rbrott committed Dec 6, 2023
1 parent d586fc3 commit 01453c2
Show file tree
Hide file tree
Showing 5 changed files with 34 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
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;
Expand All @@ -53,6 +54,8 @@
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 =
Expand Down Expand Up @@ -136,6 +139,9 @@ public DriveLocalizer() {
lastRightFrontPos = rightFront.getPositionAndVelocity().position;

lastHeading = Rotation2d.exp(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS));

// TODO: reverse encoders if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
}

@Override
Expand Down Expand Up @@ -193,6 +199,8 @@ public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
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");
Expand All @@ -203,6 +211,11 @@ public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
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));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,12 @@
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;
Expand All @@ -60,6 +60,8 @@
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 =
Expand Down Expand Up @@ -150,6 +152,9 @@ public DriveLocalizer() {
lastRightPos /= rightEncs.size();
this.rightEncs = Collections.unmodifiableList(rightEncs);
}

// TODO: reverse encoder directions if needed
// leftEncs.get(0).setDirection(DcMotorSimple.Direction.REVERSE);
}

@Override
Expand Down Expand Up @@ -205,6 +210,9 @@ public TankDrive(HardwareMap hardwareMap, Pose2d pose) {
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"));

Expand All @@ -215,6 +223,11 @@ public TankDrive(HardwareMap hardwareMap, Pose2d pose) {
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));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@ public static class Params {
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")));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,9 @@ public static class Params {
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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
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";
Expand Down

0 comments on commit 01453c2

Please sign in to comment.