Turn Degrees command works, Keenan did work on Dead Assist Control Mode

This commit is contained in:
Aarav Shah
2020-02-21 19:44:51 -07:00
parent e5a9d0c364
commit 9f1aff6c8d
5 changed files with 114 additions and 15 deletions
@@ -7,6 +7,7 @@
package frc4388.robot.commands;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpiutil.math.MathUtil;
import frc4388.robot.Constants.DriveConstants;
@@ -21,6 +22,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase {
long m_deadTimeSteer, m_deadTimeMove;
long m_deadTimeout = 100;
IHandController m_controller;
boolean m_isInterrupted;
/**
* Creates a new DriveWithJoystickUsingDeadAssistPID to control the drivetrain with an Xbox controller.
@@ -42,6 +44,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase {
@Override
public void initialize() {
m_currTime = System.currentTimeMillis();
resetGyroTarget();
}
// Called every time the scheduler runs while the command is scheduled.
@@ -54,6 +57,11 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase {
m_deltaTime = System.currentTimeMillis() - m_currTime;
m_currTime = System.currentTimeMillis();
if (m_isInterrupted) {
resetGyroTarget();
m_isInterrupted = false;
}
/* If move stick is being used */
if (moveInput != 0) {
m_deadTimeMove = m_currTime;
@@ -90,16 +98,17 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase {
}
}
private void runDriveWithInput(double move, double steer) {
private void runDriveWithInput(double move, double steerInput) {
double cosMultiplier = .45;
double steerOutput = 0;
double deadzone = .2;
/* Curves the steer output to be similarily gradual */
if (steer > 0){
steerOutput = -cosMultiplier*Math.cos(1.571*steer)+(cosMultiplier+deadzone);
} else {
steerOutput = cosMultiplier*Math.cos(1.571*steer)-(cosMultiplier+deadzone);
if (steerInput > 0){
steerOutput = -cosMultiplier*Math.cos(1.571*steerInput)+(cosMultiplier+deadzone);
} else if (steerInput < 0) {
steerOutput = cosMultiplier*Math.cos(1.571*steerInput)-(cosMultiplier+deadzone);
}
m_drive.driveWithInput(move, steerOutput);
System.out.println("Driving With Input");
}
@@ -110,8 +119,23 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase {
}
private void runStoppedTurn(double steer) {
updateGyroTarget(steer);
m_drive.runDrivePositionPID(m_stopPos, m_targetGyro);
double cosMultiplier = 0.70;
double steerOutput = 0;
double deadzone = .2;
/* Curves the steer output to be similarily gradual */
if (steer > 0) {
steerOutput = -cosMultiplier*Math.cos(1.571*steer)+(cosMultiplier+deadzone);
} else if (steer < 0) {
steerOutput = cosMultiplier*Math.cos(1.571*steer)-(cosMultiplier+deadzone);
}
updateGyroTarget(steerOutput);
double currentPos = m_drive.m_rightFrontMotorPos;
if (Math.abs(currentPos - m_stopPos) > 100) {
m_drive.runDrivePositionPID(m_stopPos, m_targetGyro);
} else {
m_drive.driveWithInputAux(0, m_targetGyro);
}
System.out.println("Turning with Target: " + m_targetGyro);
}
@@ -121,8 +145,8 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase {
private void updateGyroTarget(double steerInput) {
m_targetGyro -= 5 * steerInput * m_deltaTime;
m_targetGyro = MathUtil.clamp( m_targetGyro,
m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/8),
m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/8));
m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4),
m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/4));
}
/**
@@ -137,6 +161,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase {
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_isInterrupted = interrupted;
}
// Returns true when the command should end.
@@ -0,0 +1,73 @@
/*----------------------------------------------------------------------------*/
/* 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.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc4388.robot.Constants.DriveConstants;
import frc4388.robot.subsystems.Drive;
public class TurnDegrees extends CommandBase {
double m_targetAngle;
Drive m_drive;
double m_currentYawInTicks;
double m_targetAngleTicksIn;
double m_targetAngleTicksOut;
int i;
/**
* Creates a new TurnDeg.
*/
public TurnDegrees(double targetAngle, Drive subsystem) {
// Use addRequirements() here to declare subsystem dependencies.
m_targetAngle = targetAngle;
m_drive = subsystem;
addRequirements(m_drive);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
m_targetAngleTicksIn = (m_targetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV;
m_currentYawInTicks = (m_drive.getGyroYaw() / 360) * DriveConstants.TICKS_PER_GYRO_REV;
m_targetAngleTicksOut = m_targetAngleTicksIn + m_currentYawInTicks;
i = 0;
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_currentYawInTicks = (m_drive.getGyroYaw() / 360) * DriveConstants.TICKS_PER_GYRO_REV;
m_drive.runTurningPID(m_targetAngleTicksOut);
SmartDashboard.putNumber("Turning Error", Math.abs(m_currentYawInTicks - m_targetAngleTicksOut));
SmartDashboard.putNumber("Turning Target", m_targetAngleTicksOut);
i++;
}
// 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.getTurnRate()) < 1) && (i > 5)) {
return true;
}
return false;
}
}