Skip to content

Commit

Permalink
Move some parameters around and update some comments
Browse files Browse the repository at this point in the history
  • Loading branch information
rbrott committed Nov 6, 2019
1 parent e54d591 commit 7ecb2fe
Show file tree
Hide file tree
Showing 15 changed files with 112 additions and 198 deletions.
Original file line number Diff line number Diff line change
@@ -1,33 +1,48 @@
package org.firstinspires.ftc.teamcode.drive;

import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.control.PIDCoefficients;
import com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints;
import com.qualcomm.hardware.motors.NeveRest20Gearmotor;
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;

/*
* Constants shared between multiple drive types.
*
* TODO: Tune or adjust the following constants to fit your robot. Note that the non-final
* fields may also be edited through the dashboard (connect to the robot's WiFi network and
* navigate to https://192.168.49.1:8080/dash). Make sure to save the values here after you
* adjust them in the dashboard; **config variable changes don't persist between app restarts**.
*
* These are not the only parameters; some are located in the localizer classes, drive base classes,
* and op modes themselves.
*/
@Config
public class DriveConstants {

/*
* TODO: Tune or adjust the following constants to fit your robot. Note that the non-final
* fields may also be edited through the dashboard (connect to the robot's WiFi network and
* navigate to https://192.168.49.1:8080/dash). Make sure to save the values here after you
* adjust them in the dashboard; **config variable changes don't persist between app restarts**.
* The type of motor used on the drivetrain. While the SDK has definitions for many common
* motors, there may be slight gear ratio inaccuracies for planetary gearboxes and other
* discrepancies. Additional motor types can be defined via an interface with the
* @DeviceProperties and @MotorType annotations.
*/
private static final MotorConfigurationType MOTOR_CONFIG =
MotorConfigurationType.getMotorType(NeveRest20Gearmotor.class);
private static final double TICKS_PER_REV = MOTOR_CONFIG.getTicksPerRev();

/*
* Set the first flag appropriately. If using the built-in motor velocity PID, update
* MOTOR_VELO_PID with the tuned coefficients from DriveVelocityPIDTuner.
*/
public static final boolean RUN_USING_ENCODER = true;
public static final PIDCoefficients MOTOR_VELO_PID = null;

/*
* These are physical constants that can be determined from your robot (including the track
* width; it will be tune empirically later although a rough estimate is important). Users are
* free to chose whichever linear distance unit they would like so long as it is consistently
* used. The default values were selected with inches in mind. Road runner uses radians for
* angular distances although most angular parameters are wrapped in Math.toRadians() for
* convenience.
* convenience. Make sure to exclude any gear ratio included in MOTOR_CONFIG from GEAR_RATIO.
*/
public static double WHEEL_RADIUS = 2;
public static double GEAR_RATIO = 1; // output (wheel) speed / input (motor) speed
Expand Down Expand Up @@ -58,14 +73,15 @@ public class DriveConstants {


public static double encoderTicksToInches(double ticks) {
return WHEEL_RADIUS * 2 * Math.PI * GEAR_RATIO * ticks / TICKS_PER_REV;
return WHEEL_RADIUS * 2 * Math.PI * GEAR_RATIO * ticks / MOTOR_CONFIG.getTicksPerRev();
}

public static double rpmToVelocity(double rpm) {
return rpm * GEAR_RATIO * 2 * Math.PI * WHEEL_RADIUS / 60.0;
}

public static double getMaxRpm() {
return MOTOR_CONFIG.getMaxRPM();
return MOTOR_CONFIG.getMaxRPM() *
(RUN_USING_ENCODER ? MOTOR_CONFIG.getAchieveableMaxRPMFraction() : 1.0);
}
}

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
*/
@Config
public class StandardTrackingWheelLocalizer extends ThreeTrackingWheelLocalizer {
public static double TICKS_PER_REV = 1;
public static double TICKS_PER_REV = 0;
public static double WHEEL_RADIUS = 2; // in
public static double GEAR_RATIO = 1; // output (wheel) speed / input (encoder) speed

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.MOTOR_VELO_PID;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.RUN_USING_ENCODER;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.encoderTicksToInches;

/*
Expand Down Expand Up @@ -54,17 +56,17 @@ public SampleMecanumDriveMR(HardwareMap hardwareMap) {
motors = Arrays.asList(leftFront, leftRear, rightRear, rightFront);

for (DcMotor motor : motors) {
// TODO: decide whether or not to use the built-in velocity PID
// if you keep it, then don't tune kStatic or kA
// otherwise, comment out the following line
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
if (RUN_USING_ENCODER) {
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
}

// TODO: reverse any motors using DcMotor.setDirection()
if (RUN_USING_ENCODER && MOTOR_VELO_PID != null) {
setPIDCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, MOTOR_VELO_PID);
}

// TODO: set the tuned coefficients from DriveVelocityPIDTuner if using RUN_USING_ENCODER
// setPIDCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, ...);
// TODO: reverse any motors using DcMotor.setDirection()

// TODO: if desired, use setLocalizer() to change the localization method
// for instance, setLocalizer(new ThreeTrackingWheelLocalizer(...));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.MOTOR_VELO_PID;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.RUN_USING_ENCODER;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.encoderTicksToInches;

/*
Expand Down Expand Up @@ -49,17 +51,17 @@ public SampleMecanumDriveREV(HardwareMap hardwareMap) {
motors = Arrays.asList(leftFront, leftRear, rightRear, rightFront);

for (DcMotorEx motor : motors) {
// TODO: decide whether or not to use the built-in velocity PID
// if you keep it, then don't tune kStatic or kA
// otherwise, comment out the following line
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
if (RUN_USING_ENCODER) {
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
}

// TODO: reverse any motors using DcMotor.setDirection()
if (RUN_USING_ENCODER && MOTOR_VELO_PID != null) {
setPIDCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, MOTOR_VELO_PID);
}

// TODO: set the tuned coefficients from DriveVelocityPIDTuner if using RUN_USING_ENCODER
// setPIDCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, ...);
// TODO: reverse any motors using DcMotor.setDirection()

// TODO: if desired, use setLocalizer() to change the localization method
// for instance, setLocalizer(new ThreeTrackingWheelLocalizer(...));
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
package org.firstinspires.ftc.teamcode.drive.mecanum;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.MOTOR_VELO_PID;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.RUN_USING_ENCODER;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.encoderTicksToInches;

import android.support.annotation.NonNull;
import com.acmerobotics.roadrunner.control.PIDCoefficients;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import java.util.ArrayList;
Expand Down Expand Up @@ -54,17 +55,17 @@ public SampleMecanumDriveREVOptimized(HardwareMap hardwareMap) {
motors = Arrays.asList(leftFront, leftRear, rightRear, rightFront);

for (ExpansionHubMotor motor : motors) {
// TODO: decide whether or not to use the built-in velocity PID
// if you keep it, then don't tune kStatic or kA
// otherwise, comment out the following line
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
if (RUN_USING_ENCODER) {
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
}

// TODO: reverse any motors using DcMotor.setDirection()
if (RUN_USING_ENCODER && MOTOR_VELO_PID != null) {
setPIDCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, MOTOR_VELO_PID);
}

// TODO: set the tuned coefficients from DriveVelocityPIDTuner if using RUN_USING_ENCODER
// setPIDCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, ...);
// TODO: reverse any motors using DcMotor.setDirection()

// TODO: if desired, use setLocalizer() to change the localization method
// for instance, setLocalizer(new ThreeTrackingWheelLocalizer(...));
Expand Down
Original file line number Diff line number Diff line change
@@ -1,18 +1,22 @@
package org.firstinspires.ftc.teamcode.drive.opmode;

import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.tuning.AccelRegression;
import com.acmerobotics.roadrunner.tuning.RampRegression;
import com.acmerobotics.roadrunner.util.NanoClock;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.RobotLog;

import org.firstinspires.ftc.robotcore.internal.system.Misc;
import org.firstinspires.ftc.teamcode.drive.mecanum.SampleMecanumDriveBase;
import org.firstinspires.ftc.teamcode.drive.mecanum.SampleMecanumDriveREV;
import org.firstinspires.ftc.teamcode.util.LoggingUtil;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.RUN_USING_ENCODER;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.getMaxRpm;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.rpmToVelocity;

Expand All @@ -34,6 +38,13 @@ public class DriveFeedforwardTuner extends LinearOpMode {

@Override
public void runOpMode() throws InterruptedException {
if (RUN_USING_ENCODER) {
RobotLog.setGlobalErrorMsg("Feedforward constants usually don't need to be tuned " +
"when using the built-in drive motor velocity PID.");
}

telemetry = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());

SampleMecanumDriveBase drive = new SampleMecanumDriveREV(hardwareMap);

NanoClock clock = NanoClock.system();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.RUN_USING_ENCODER;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kV;

/*
Expand Down Expand Up @@ -125,6 +126,11 @@ private void removePidVariable() {

@Override
public void runOpMode() {
if (!RUN_USING_ENCODER) {
RobotLog.setGlobalErrorMsg("%s does not need to be run if the built-in motor velocity" +
"PID is not in use", getClass().getSimpleName());
}

telemetry = new MultipleTelemetry(telemetry, dashboard.getTelemetry());

drive = new SampleMecanumDriveREV(hardwareMap);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@
import org.firstinspires.ftc.teamcode.drive.mecanum.SampleMecanumDriveREV;

/*
* Op mode for tuning follower PID coefficients. The robot drives in a DISTANCE-by-DISTANCE square
* indefinitely.
* Op mode for tuning follower PID coefficients (located in the drive base classes). The robot
* drives in a DISTANCE-by-DISTANCE square indefinitely.
*/
@Config
@Autonomous(group = "drive")
Expand Down
Loading

0 comments on commit 7ecb2fe

Please sign in to comment.