Variable Constants

This commit is contained in:
aborunda
2021-10-25 18:02:23 -06:00
parent 690bad77c5
commit 695ddfca77
4 changed files with 39 additions and 17 deletions
@@ -8,6 +8,7 @@
package frc4388.robot.commands.drive;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc4388.robot.Constants;
import frc4388.robot.Robot;
import frc4388.robot.Constants.DriveConstants;
import frc4388.robot.subsystems.Drive;
@@ -43,15 +44,8 @@ public class DriveWithJoystick extends CommandBase {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double moveInput;
double steerInput;
if (Robot.lastIsTest()) {
moveInput = m_controller.getLeftYAxis() / 2;
steerInput = m_controller.getRightXAxis() / 2;
} else {
moveInput = m_controller.getLeftYAxis();
steerInput = m_controller.getRightXAxis();
}
double moveInput = m_controller.getLeftYAxis();
double steerInput = m_controller.getRightXAxis();
double moveOutput = 0;
double steerOutput = 0;
@@ -60,7 +54,8 @@ public class DriveWithJoystick extends CommandBase {
} else {
moveOutput = Math.cos(1.571*moveInput)-1;
}
moveOutput *= DriveConstants.DRIVE_WITH_JOYSTICK_FACTOR;
System.out.println(moveOutput);
double cosMultiplier;
double deadzone = .1;