5 Commits

Author SHA1 Message Date
Tylr-J42
6c0df54b06 fixing dt bindings divide by zero flaw 2025-06-06 18:22:12 -04:00
Tylr-J42
fa34ef00fe exponents on joystick now implemented correctly 2025-05-19 19:06:48 -04:00
Tylr-J42
68da3c630c Noah WTF are you smoking? (fixed driver bindings) 2025-05-19 01:55:28 -04:00
c9316cebc3 end of mayhem 2025-05-19 01:48:50 -04:00
d312e125cd before mayhem elims 2025-05-17 13:48:42 -04:00
8 changed files with 31 additions and 17 deletions

View File

@@ -16,12 +16,12 @@
},
{
"anchor": {
"x": 3.6442622950819668,
"y": 5.031967213114754
"x": 3.609900518622585,
"y": 5.005924534374863
},
"prevControl": {
"x": 3.328722911520323,
"y": 5.557866185717494
"x": 3.2943611350609414,
"y": 5.531823506977602
},
"nextControl": null,
"isLocked": false,

View File

@@ -3,13 +3,13 @@
"waypoints": [
{
"anchor": {
"x": 3.6442622950819668,
"y": 5.031967213114754
"x": 3.609900518622585,
"y": 5.005924534374863
},
"prevControl": null,
"nextControl": {
"x": 3.5117625600811717,
"y": 5.243966789116026
"x": 3.47740078362179,
"y": 5.217924110376135
},
"isLocked": false,
"linkedName": "L"

View File

@@ -7,7 +7,7 @@ package frc.robot;
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.Logger;
//import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGReader;
import org.littletonrobotics.junction.wpilog.WPILOGWriter;

View File

@@ -111,9 +111,9 @@ public class RobotContainer {
drivetrain.setDefaultCommand(
drivetrain.drive(
() -> driver.getLeftY() * Math.pow(Math.abs(driver.getLeftY()) + Math.abs(driver.getLeftX()), 3),
() -> driver.getLeftX() * Math.pow(Math.abs(driver.getLeftY()) + Math.abs(driver.getLeftX()), 3),
driver::getRightX, //Math.signum(driver.getRightX()) * Math.pow(driver.getRightX(), 3)
() -> driver.getLeftY(),
() -> driver.getLeftX(),
() -> driver.getRightX(),
() -> true
)
);

View File

@@ -16,6 +16,8 @@ public class AutoConstants {
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
public static final double kMaxSpeedMetersPerSecondAutoAlign = 2.5;
public static final double kPXYController = 3.5;
public static final double kPThetaController = 5;

View File

@@ -13,7 +13,7 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
public class DrivetrainConstants {
// Driving Parameters - Note that these are not the maximum capable speeds of
// the robot, rather the allowed maximum speeds
public static final double kMaxSpeedMetersPerSecond = 5.5;
public static final double kMaxSpeedMetersPerSecond = 5.5 * 0.75;
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
// Chassis configuration

View File

@@ -9,4 +9,6 @@ public class OIConstants {
public static final String kAutoTab = "Auto Tab";
public static final String kSensorsTab = "Sensors Tab";
public static final String kApriltagTab = "Apriltag Tab";
public static final double kJoystickExponential = 3;
}

View File

@@ -323,8 +323,18 @@ public class Drivetrain extends SubsystemBase {
*/
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
// Convert the commanded speeds into the correct units for the drivetrain
double xSpeedDelivered = xSpeed * DrivetrainConstants.kMaxSpeedMetersPerSecond;
double ySpeedDelivered = ySpeed * DrivetrainConstants.kMaxSpeedMetersPerSecond;
double p = Math.sqrt(Math.pow(xSpeed, 2) + Math.pow(ySpeed, 2));
double xSpeedDelivered = 0;
double ySpeedDelivered = 0;
if(p != 0){
xSpeedDelivered = xSpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
ySpeedDelivered = ySpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
}else{
xSpeedDelivered = 0;
ySpeedDelivered = 0;
}
double rotDelivered = rot * DrivetrainConstants.kMaxAngularSpeed;
var swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
@@ -362,8 +372,8 @@ public class Drivetrain extends SubsystemBase {
);
double speed = Math.hypot(controlEffort.vxMetersPerSecond, controlEffort.vyMetersPerSecond);
if (speed > AutoConstants.kMaxSpeedMetersPerSecond) {
double mul = AutoConstants.kMaxSpeedMetersPerSecond / speed;
if (speed > AutoConstants.kMaxSpeedMetersPerSecondAutoAlign) {
double mul = AutoConstants.kMaxSpeedMetersPerSecondAutoAlign / speed;
controlEffort.vxMetersPerSecond *= mul;
controlEffort.vyMetersPerSecond *= mul;
}