Add Distance PID Command

This commit is contained in:
Aarav
2020-01-16 20:11:48 -07:00
parent 686e9feb00
commit 6fc414ccb8
3 changed files with 67 additions and 11 deletions
@@ -15,6 +15,7 @@ import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc4388.robot.Constants.*;
import frc4388.robot.commands.DriveToDistancePID;
import frc4388.robot.subsystems.Drive;
import frc4388.robot.subsystems.LED;
import frc4388.utility.LEDPatterns;
@@ -72,7 +73,7 @@ public class RobotContainer {
/* PID Test Command */
new JoystickButton(getDriverJoystick(), XboxController.B_BUTTON)
.whileHeld(() -> m_robotDrive.goToTargetPos(), m_robotDrive);
.whenPressed(new DriveToDistancePID(m_robotDrive, 5000));
}
/**
@@ -0,0 +1,57 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package frc4388.robot.commands;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc4388.robot.subsystems.Drive;
public class DriveToDistancePID extends CommandBase {
Drive m_drive;
double m_distance;
double m_leftTarget;
double m_rightTarget;
/**
* Creates a new DriveToDistancePID.
*/
public DriveToDistancePID(Drive subsystem, double distance) {
// Use addRequirements() here to declare subsystem dependencies.
m_drive = subsystem;
m_distance = distance;
addRequirements(m_drive);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
m_leftTarget = m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() + m_distance;
m_rightTarget = m_drive.m_rightFrontMotor.getActiveTrajectoryPosition() + m_distance;
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_drive.gotoPositionPID(m_drive.m_leftFrontMotor, m_leftTarget);
m_drive.gotoPositionPID(m_drive.m_rightFrontMotor, m_rightTarget);
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
if (Math.abs(m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() - m_leftTarget) < 100){
return true;
} else {
return false;
}
}
}
@@ -179,6 +179,14 @@ public class Drive extends SubsystemBase {
m_driveTrain.arcadeDrive(move, steer);
}
public void gotoPositionPID(WPI_TalonFX talon, double targetPos) {
talon.set(TalonFXControlMode.Position, targetPos);
}
public void gotoVelocityPID(WPI_TalonFX talon, double targetVel) {
talon.set(TalonFXControlMode.Velocity, targetVel);
}
public double getGyroYaw() {
double[] ypr = new double[3];
m_pigeon.getYawPitchRoll(ypr);
@@ -201,14 +209,4 @@ public class Drive extends SubsystemBase {
m_pigeon.setYaw(0);
m_pigeon.setAccumZAngle(0);
}
// Motion Magic Testing
public void goToTargetPos()
{
//double targetPos = XboxController.RIGHT_Y_AXIS * DriveConstants.ENCODER_TICKS_PER_REV * 10.0;
double targetPos = 1000;
m_leftFrontMotor.set(TalonFXControlMode.Velocity, targetPos);
m_rightFrontMotor.set(TalonFXControlMode.Velocity, -targetPos);
}
}