Skip to content
This repository has been archived by the owner on Dec 30, 2024. It is now read-only.

Commit

Permalink
changing motor configuration is easier and readme updates
Browse files Browse the repository at this point in the history
  • Loading branch information
AnyiLin committed Aug 27, 2024
1 parent 13e503c commit 93db7dc
Show file tree
Hide file tree
Showing 12 changed files with 96 additions and 51 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,8 @@ that applies to you and follow the directions there.

# Drive Encoders
* First, you'll need all of your drive motors to have encoders attached.
* Then, go to `DriveEncoderLocalizer.java`. Go to where it tells you to replace the current statements with your encoder ports in the constructor.
Replace the `deviceName` parameter with the name of the port that the encoder for each motor is connected
to. The names of the variables is where on the robot the corresponding motor should be.
* Then, go to `DriveEncoderLocalizer.java`. The motor names are already set, so you don't have to do
anything to change the encoder names there.
* Then, reverse the direction of any encoders so that all encoders tick up when the robot is moving forward.
* Now, you'll have to tune the multipliers. These convert your measurements from encoder ticks into
inches or radians, essentially scaling your localizer so that your numbers are accurate to the real
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,6 @@ implementation 'com.acmerobotics.dashboard:dashboard:0.4.5'
4. Find the `build.gradle` file under the `teamcode` folder.
5. In this gradle file, add the following dependency:
```
implementation 'com.fasterxml/jackson.core:jacson-databind:2.12.7'
implementation 'com.fasterxml/jackson.core:jackson-databind:2.12.7'
implementation 'org.jetbrains.kotlin:kotlin-stdlib:1.4.21'
```
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@ measurements will be in centimeters.

## Tuning
* To start with, we need the mass of the robot in kg. This is used for the centripetal force correction,
and the mass should be put on line `80` in the `FollowerConstants` class under the
`tuning` package.
and the mass, with the variable name `mass`, should be put on line `86` in the `FollowerConstants`
class under the `tuning` package.

* Next, we need to find the preferred mecanum drive vectors. The rollers on mecanum wheels point at a
45 degree angle from the forward direction, but the actual direction the force is output is actually
Expand All @@ -26,9 +26,9 @@ measurements will be in centimeters.
Dashboard under the dropdown for each respective class, but higher distances work better. After the
distance has finished running, the end velocity will be output to telemetry. The robot may continue
to drift a little bit after the robot has finished running the distance, so make sure you have
plenty of room. Once you're done, put the velocity for the `Forward Velocity Tuner` on line `27` in
the `FollowerConstants` class, and the velocity for the `Strafe Velocity Tuner` on line `28` in the
`FollowerConstants` class.
plenty of room. Once you're done, put the velocity for the `Forward Velocity Tuner` on line `33` in
the `FollowerConstants` class, and the velocity for the `Strafe Velocity Tuner` on line `34` in the
`FollowerConstants` class. The variable names should be `xMovement` and `yMovement`, respectively.

* The last set of automatic tuners you'll need to run are the zero power acceleration tuners. These
find the rate at which your robot decelerates when power is cut from the drivetrain. This is used to
Expand All @@ -41,9 +41,10 @@ measurements will be in centimeters.
which point it will display the deceleration in telemetry. This robot will need to drift to a stop
to properly work, and the higher the velocity the greater the drift distance, so make sure you have
enough room. Once you're done, put the zero power acceleration for the
`Forward Zero Power Acceleration Tuner` on line `88` in the `FollowerConstants` class and the zero
power acceleration for the `Lateral Zero Power Acceleration Tuner` on line `92` in the
`FollowerConstants` class.
`Forward Zero Power Acceleration Tuner` on line `94` in the `FollowerConstants` class and the zero
power acceleration for the `Lateral Zero Power Acceleration Tuner` on line `98` in the
`FollowerConstants` class. The variable names should be `forwardZeroPowerAcceleration` and
`lateralZeroPowerAcceleration`, respectively.

* After this, we will want to tune the translational PID. Go to FTC Dashboard and disable all but
the `useTranslational` checkboxes under the `Follower` tab. Then, run `StraightBackAndForth`. Make
Expand All @@ -69,8 +70,8 @@ measurements will be in centimeters.
`zeroPowerAccelerationMultiplier`. This determines how fast your robot will decelerate as a factor
of how fast your robot will coast to a stop. Honestly, this is up to you. I personally used 4, but
what works best for you is most important. Higher numbers will cause a faster brake, but increase
oscillations at the end. Lower numbers will do the opposite. This can be found on line `101` in
`FollowerConstants`. The drive PID is much, much more sensitive than the others. For reference,
oscillations at the end. Lower numbers will do the opposite. This can be found on line `107` in
`FollowerConstants`, named `zeroPowerAccelerationMultiplier`. The drive PID is much, much more sensitive than the others. For reference,
my P values were in the hundredths and thousandths place values, and my D values were in the hundred
thousandths and millionths place values. To tune this, enable `useDrive`, `useHeading`, and
`useTranslational` in the `Follower` dropdown in FTC Dashboard. Next, run `StraightBackAndForth`
Expand All @@ -95,7 +96,7 @@ measurements will be in centimeters.
* Finally, we will want to tune the centripetal force correction. This is a pretty simple tune. Open
up FTC Dashboard and enable everything under the `Follower` tab. Then, run `CurvedBackAndForth`
and turn off its timer. If you notice the robot is correcting towards the inside of the curve
as/after running a path, then increase `centripetalScaling`, which can be found on line `83` of
as/after running a path, then increase `centripetalScaling`, which can be found on line `89` of
`FollowerConstants`. If the robot is correcting towards the outside of the curve, then decrease
`centripetalScaling`.

Expand All @@ -108,8 +109,9 @@ measurements will be in centimeters.
## Note About the PIDs
In versions of Pedro Pathing before early August 2024, there were 2 PIDs used in the translational,
heading, and drive control. However, now there is only one main PID. The old system can still be used.
Scroll down to the bottom of `FollowerConstants` and set all the booleans from lines `151` to `153`
to true. This will enable the two PID system that Pedro Pathing originally used. From there, scroll
Scroll down to the bottom of `FollowerConstants` and set all the booleans from lines `157` to `159`
to true. They should be named `useSecondaryTranslationalPID`, `useSecondaryHeadingPID`, and `useSecondaryDrivePID`.
This will enable the two PID system that Pedro Pathing originally used. From there, scroll
down and all the values pertaining to the secondary PIDs will be there. The two PID system works with
a PID that handles larger errors (the main PID) and a second PID to handle smaller errors (the
secondary PID). The main PID should be tuned to move the error within the secondary PID's range
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
package org.firstinspires.ftc.teamcode.pedroPathing.examples;

import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
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 com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
Expand Down Expand Up @@ -32,10 +37,10 @@ public class TeleOpEnhancements extends OpMode {
public void init() {
follower = new Follower(hardwareMap);

leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftRear = hardwareMap.get(DcMotorEx.class, "leftRear");
rightRear = hardwareMap.get(DcMotorEx.class, "rightRear");
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);
rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName);
rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName);

leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftRear.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.headingPIDFSwitch;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.drivePIDFFeedForward;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.headingPIDFFeedForward;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
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.translationalPIDFFeedForward;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.lateralZeroPowerAcceleration;
import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryDrivePIDFFeedForward;
Expand Down Expand Up @@ -158,10 +162,10 @@ public void initialize() {
driveVectorScaler = new DriveVectorScaler(FollowerConstants.frontLeftVector);
poseUpdater = new PoseUpdater(hardwareMap);

leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftRear = hardwareMap.get(DcMotorEx.class, "leftRear");
rightRear = hardwareMap.get(DcMotorEx.class, "rightRear");
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
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);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
package org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers;

import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
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 com.acmerobotics.dashboard.config.Config;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.HardwareMap;
Expand All @@ -20,7 +25,7 @@
* @version 1.0, 4/2/2024
*/
@Config
public class DriveEncoderLocalizer extends Localizer { // todo: make drive encoders work
public class DriveEncoderLocalizer extends Localizer {
private HardwareMap hardwareMap;
private Pose startPose;
private Pose displacementPose;
Expand Down Expand Up @@ -59,11 +64,10 @@ public DriveEncoderLocalizer(HardwareMap map) {
public DriveEncoderLocalizer(HardwareMap map, Pose setStartPose) {
hardwareMap = map;

// TODO: replace these with your encoder ports
leftFront = new Encoder(hardwareMap.get(DcMotorEx.class, "leftFront"));
rightFront = new Encoder(hardwareMap.get(DcMotorEx.class, "rightFront"));
leftRear = new Encoder(hardwareMap.get(DcMotorEx.class, "leftRear"));
rightRear = new Encoder(hardwareMap.get(DcMotorEx.class, "rightRear"));
leftFront = new Encoder(hardwareMap.get(DcMotorEx.class, leftFrontMotorName));
leftRear = new Encoder(hardwareMap.get(DcMotorEx.class, leftRearMotorName));
rightRear = new Encoder(hardwareMap.get(DcMotorEx.class, rightRearMotorName));
rightFront = new Encoder(hardwareMap.get(DcMotorEx.class, rightFrontMotorName));

// TODO: reverse any encoders necessary
leftFront.setDirection(Encoder.REVERSE);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning;

import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
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 com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
Expand Down Expand Up @@ -48,10 +53,10 @@ public void init() {

dashboardPoseTracker = new DashboardPoseTracker(poseUpdater);

leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftRear = hardwareMap.get(DcMotorEx.class, "leftRear");
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
rightRear = hardwareMap.get(DcMotorEx.class, "rightRear");
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,12 @@
@Config
public class FollowerConstants {

// This section is for configuring your motors
public static String leftFrontMotorName = "leftFront";
public static String leftRearMotorName = "leftRear";
public static String rightFrontMotorName = "rightFront";
public static String rightRearMotorName = "rightRear";

// 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;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
package org.firstinspires.ftc.teamcode.pedroPathing.tuning;

import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
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 com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
Expand Down Expand Up @@ -62,10 +67,10 @@ public class ForwardVelocityTuner extends OpMode {
public void init() {
poseUpdater = new PoseUpdater(hardwareMap);

leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftRear = hardwareMap.get(DcMotorEx.class, "leftRear");
rightRear = hardwareMap.get(DcMotorEx.class, "rightRear");
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
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);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
package org.firstinspires.ftc.teamcode.pedroPathing.tuning;

import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
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 com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
Expand Down Expand Up @@ -65,10 +70,10 @@ public class ForwardZeroPowerAccelerationTuner extends OpMode {
public void init() {
poseUpdater = new PoseUpdater(hardwareMap);

leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftRear = hardwareMap.get(DcMotorEx.class, "leftRear");
rightRear = hardwareMap.get(DcMotorEx.class, "rightRear");
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
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);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
package org.firstinspires.ftc.teamcode.pedroPathing.tuning;

import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName;
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 com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
Expand Down Expand Up @@ -65,10 +70,10 @@ public class LateralZeroPowerAccelerationTuner extends OpMode {
public void init() {
poseUpdater = new PoseUpdater(hardwareMap);

leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
leftRear = hardwareMap.get(DcMotorEx.class, "leftRear");
rightRear = hardwareMap.get(DcMotorEx.class, "rightRear");
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
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);
Expand Down
Loading

0 comments on commit 93db7dc

Please sign in to comment.