Skip to content

Commit

Permalink
Additional Changes before first meeting
Browse files Browse the repository at this point in the history
I made a few additional changes/removed some stuff before the first meeting that's coming up in a few days.
  • Loading branch information
ErikCald committed Jun 26, 2021
1 parent 0ac2669 commit 9fa697d
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@ public class RamseteControllerLogging extends RamseteController {

NetworkTableEntry xError, yError, rotError;

public RamseteControllerLogging() {
super(Config.kRamseteB, Config.kRamseteZeta);
public RamseteControllerLogging(double b, double zeta) {
super(b, zeta);

var table = NetworkTableInstance.getDefault().getTable("DrivetrainData");
xError = table.getEntry("xError");
Expand Down
20 changes: 1 addition & 19 deletions src/main/java/frc/robot/config/Config.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,25 +33,7 @@ public final class Config {
public static final boolean DRIVETRAIN_LEFT_SENSORPHASE = true;
public static final boolean DRIVETRAIN_RIGHT_SENSORPHASE = true;

public static final double kTrackwidthMeters = 0.69;
public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(
kTrackwidthMeters);

public static final double drivetrainWheelDiameter = 0.1524;
public static final double ticksPerRevolution = 4096;

public static final double kMaxSpeedMetersPerSecond = 1;
public static final double kMaxAccelerationMetersPerSecondSquared = 0.5;

public static final double RAMSETE_KF = 0.5; // Rough/quick tuning.
public static final double RAMSETE_KP = 0.15;
public static final double RAMSETE_KI = 0;
public static final double RAMSETE_KD = 0;
public static final double RAMSETE_ALLOWABLE_PID_ERROR = 0;

// Reasonable baseline values for a RAMSETE follower in units of meters and seconds
public static final double kRamseteB = 2;
public static final double kRamseteZeta = 0.7;
public static final double RAMSETE_KF = 0;

/** Setup for ArcadeDrive */
public static int LEFT_CONTROL_STICK_Y = 1;
Expand Down
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ private void setTalonConfigurations() {
TalonSRXConfiguration talonConfig = new TalonSRXConfiguration();

/** Put any settings in TalonSRXConfiguration here. */

talonConfig.slot1.kF = Config.RAMSETE_KF;


// Error Code check all TalonSRXConfiguration settings
Expand All @@ -93,6 +93,10 @@ private void setTalonConfigurations() {
leftLeader.setSensorPhase(Config.DRIVETRAIN_LEFT_SENSORPHASE);
rightLeader.setSensorPhase(Config.DRIVETRAIN_RIGHT_SENSORPHASE);

// Ramsete set to slot 1 so any future Driver controls can be slot 1
leftLeader.selectProfileSlot(1, 0);
rightLeader.selectProfileSlot(1, 0);

// Set brake mode for testing so it immediatly stops moving if something goes wrong
leftLeader.setNeutralMode(NeutralMode.Brake);
rightLeader.setNeutralMode(NeutralMode.Brake);
Expand Down Expand Up @@ -120,8 +124,8 @@ private Rotation2d getCurrentAngle() {


/**
* Sets the velocity of the left and right side of the drivetrain.
* Used for ramsete.
* Sets the velocity of the left and right side of the drivetrain in meters per second.
* Called by RamseteCommand
*/
public void tankDriveVelocity(double leftVel, double rightVel) {

Expand Down

0 comments on commit 9fa697d

Please sign in to comment.