mirror of
https://github.com/Team4388/2024AcrossTheRidgebotiverse.git
synced 2026-06-09 00:38:02 -06:00
talon stuff
This commit is contained in:
@@ -182,8 +182,8 @@ public class RobotContainer {
|
|||||||
// ! Swerve Drive Default Command (Regular Rotation)
|
// ! Swerve Drive Default Command (Regular Rotation)
|
||||||
m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> {
|
m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> {
|
||||||
m_robotSwerveDrive.driveWithInput(getDeadbandedDriverController().getRightTrigger(),
|
m_robotSwerveDrive.driveWithInput(getDeadbandedDriverController().getRightTrigger(),
|
||||||
getDeadbandedDriverController().getRight(),
|
getDeadbandedDriverController().getRight().times(-1),
|
||||||
true);
|
false);
|
||||||
}, m_robotSwerveDrive)
|
}, m_robotSwerveDrive)
|
||||||
.withName("SwerveDrive DefaultCommand"));
|
.withName("SwerveDrive DefaultCommand"));
|
||||||
m_robotSwerveDrive.hellsHorses();
|
m_robotSwerveDrive.hellsHorses();
|
||||||
|
|||||||
@@ -84,7 +84,9 @@ public class SwerveDrive extends SubsystemBase {
|
|||||||
// Convert field-relative speeds to robot-relative speeds.
|
// Convert field-relative speeds to robot-relative speeds.
|
||||||
chassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(-1 * speed.getX(), -1 * speed.getY(), rightStick.getX() * rotSpeedAdjust, gyro.getRotation2d());//.times(-1));
|
chassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(-1 * speed.getX(), -1 * speed.getY(), rightStick.getX() * rotSpeedAdjust, gyro.getRotation2d());//.times(-1));
|
||||||
} else { // Create robot-relative speeds.
|
} else { // Create robot-relative speeds.
|
||||||
chassisSpeeds = new ChassisSpeeds(-1 * leftStick.getX(), -1 * leftStick.getY(), -1 * rightStick.getX() * SwerveDriveConstants.ROTATION_SPEED);
|
Translation2d speed = leftStick.times(leftStick.getNorm() * speedAdjust);
|
||||||
|
|
||||||
|
chassisSpeeds = new ChassisSpeeds(-1 * speed.getX(), -1 * speed.getY(), -1 * rightStick.getX() * SwerveDriveConstants.ROTATION_SPEED);
|
||||||
}
|
}
|
||||||
setModuleStates(kinematics.toSwerveModuleStates(chassisSpeeds));
|
setModuleStates(kinematics.toSwerveModuleStates(chassisSpeeds));
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -19,6 +19,7 @@ import edu.wpi.first.math.geometry.Rotation2d;
|
|||||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||||
import edu.wpi.first.math.util.Units;
|
import edu.wpi.first.math.util.Units;
|
||||||
|
import edu.wpi.first.wpilibj.DriverStation;
|
||||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
import frc4388.robot.Constants.SwerveDriveConstants;
|
import frc4388.robot.Constants.SwerveDriveConstants;
|
||||||
@@ -63,15 +64,17 @@ public class SwerveModule extends SubsystemBase {
|
|||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
|
if (DriverStation.isEnabled()) {
|
||||||
|
System.out.println("Drive Velocity_60FT_NoRunup: " + selfid + ", " + getDriveVel());
|
||||||
|
System.out.println("Drive Powerdraw_60FT_NoRunup: " + selfid + ", " + driveMotor.getMotorOutputVoltage());
|
||||||
|
}
|
||||||
//encoder.configMagnetOffset(offsetGetter.get());
|
//encoder.configMagnetOffset(offsetGetter.get());
|
||||||
//SmartDashboard.putString("Error Code: " + selfid, getstuff());
|
//SmartDashboard.putString("Error Code: " + selfid, getstuff());
|
||||||
// SmartDashboard.putNumber("Angular Position: " + selfid, getAngle().getDegrees());
|
// SmartDashboard.putNumber("Angular Position: " + selfid, getAngle().getDegrees());
|
||||||
// SmartDashboard.putNumber("Angular Velocity: " + selfid, getAngularVel());
|
// SmartDashboard.putNumber("Angular Velocity: " + selfid, getAngularVel());
|
||||||
// SmartDashboard.putNumber("Drive Position: " + selfid, getDrivePos());
|
// SmartDashboard.putNumber("Drive Position: " + selfid, getDrivePos());
|
||||||
SmartDashboard.putNumber("Drive Velocity: " + selfid, getDriveVel());
|
// SmartDashboard.putNumber("Drive Velocity: " + selfid, getDriveVel());
|
||||||
SmartDashboard.putNumber("Drive Powerdraw: " + selfid, driveMotor.getMotorOutputVoltage());
|
// SmartDashboard.putNumber("Drive Powerdraw: " + selfid, driveMotor.getMotorOutputVoltage());
|
||||||
System.out.println("Drive Velocity: " + selfid + ", " + getDriveVel());
|
|
||||||
System.out.println("Drive Powerdraw: " + selfid + ", " + driveMotor.getMotorOutputVoltage());
|
|
||||||
|
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
|
|||||||
@@ -16,6 +16,7 @@ public class DeadbandedXboxController extends XboxController {
|
|||||||
public Translation2d getLeft() { return skewToDeadzonedCircle(super.getLeftX(), super.getLeftY()); }
|
public Translation2d getLeft() { return skewToDeadzonedCircle(super.getLeftX(), super.getLeftY()); }
|
||||||
public Translation2d getRight() { return skewToDeadzonedCircle(-super.getRightX(), super.getRightY()); }
|
public Translation2d getRight() { return skewToDeadzonedCircle(-super.getRightX(), super.getRightY()); }
|
||||||
public Translation2d getRightTrigger() {return skewToDeadzonedCircle(0, -getRightTriggerAxis() + getLeftTriggerAxis());}
|
public Translation2d getRightTrigger() {return skewToDeadzonedCircle(0, -getRightTriggerAxis() + getLeftTriggerAxis());}
|
||||||
|
public Translation2d getFixed() {return skewToDeadzonedCircle(0, -0.8);}
|
||||||
public static Translation2d skewToDeadzonedCircle(double x, double y) {
|
public static Translation2d skewToDeadzonedCircle(double x, double y) {
|
||||||
Translation2d translation2d = new Translation2d(x, y);
|
Translation2d translation2d = new Translation2d(x, y);
|
||||||
double magnitude = translation2d.getNorm();
|
double magnitude = translation2d.getNorm();
|
||||||
|
|||||||
Reference in New Issue
Block a user