Skip to content

Commit

Permalink
Couple tweaks
Browse files Browse the repository at this point in the history
Made a couple tweaks before other students use this code as a base to build upon.
  • Loading branch information
ErikCald committed Jun 25, 2021
1 parent b8b1238 commit 90d0d4e
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 8 deletions.
5 changes: 2 additions & 3 deletions RamsetePractice/src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import frc.robot.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;


/**
* This class is where the bulk of the robot should be declared. Since
Expand Down Expand Up @@ -55,7 +55,6 @@ private void configureButtonBindings() {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
// Create your RamseteCommand here and have this method return the instance of it.
return new InstantCommand();
return new InstantCommand(); // Temporary. Replace this.
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,14 @@
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.trajectory.Trajectory;
import frc.robot.config.Config;

public class RamseteControllerLogging extends RamseteController {

NetworkTableEntry xError, yError, rotError;

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

var table = NetworkTableInstance.getDefault().getTable("DrivetrainData");
xError = table.getEntry("xError");
Expand Down
4 changes: 3 additions & 1 deletion RamsetePractice/src/main/java/frc/robot/config/Config.java
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,9 @@ public final class Config {
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;

/** Setup for ArcadeDrive */
public static int LEFT_CONTROL_STICK_Y = 1;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
import com.ctre.phoenix.sensors.PigeonIMU.FusionStatus;

import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.config.Config;

Expand Down Expand Up @@ -108,13 +109,13 @@ public final void arcadeDrive(double forwardVal, double rotateVal, boolean squar
m_differentialDrive.arcadeDrive(forwardVal, rotateVal, squareInputs);
}

private double getCurrentAngle() {
private Rotation2d getCurrentAngle() {
FusionStatus status = new FusionStatus();
double angle = pigeon.getFusedHeading(status);

ErrorCode error = status.lastError; // ErrorCode to check

return angle;
return Rotation2d.fromDegrees(angle);
}


Expand All @@ -123,7 +124,7 @@ private double getCurrentAngle() {
* Used for ramsete.
*/
public void tankDriveVelocity(double leftVel, double rightVel) {

}

@Override
Expand Down

0 comments on commit 90d0d4e

Please sign in to comment.