Swerve + Constant

This commit is contained in:
Antoine PerreaultE 2024-01-22 19:33:18 -05:00
parent 27e57ca157
commit b1efbc8373
10 changed files with 240 additions and 13 deletions

View File

@ -0,0 +1,8 @@
{
"angleJoystickRadiusDeadband": 0.5,
"heading": {
"p": 0.4,
"i": 0,
"d": 0.01
}
}

View File

@ -0,0 +1,30 @@
{
"location": {
"front": -12.375,
"left": 12.375
},
"absoluteEncoderOffset": 80.332,
"drive": {
"type": "sparkmax",
"id": 8,
"canbus": null
},
"angle": {
"type": "sparkmax",
"id": 9,
"canbus": null
},
"inverted": {
"angle": true,
"drive": false
},
"conversionFactor": {
"angle": 0,
"drive": 0
},
"encoder": {
"type": "cancoder",
"id": 7,
"canbus": null
}
}

View File

@ -0,0 +1,30 @@
{
"location": {
"front": -12.375,
"left": -12.375
},
"absoluteEncoderOffset": 28.74,
"drive": {
"type": "sparkmax",
"id": 11,
"canbus": null
},
"angle": {
"type": "sparkmax",
"id": 12,
"canbus": null
},
"inverted": {
"angle": true,
"drive": false
},
"conversionFactor": {
"angle": 0,
"drive": 0
},
"encoder": {
"type": "cancoder",
"id": 6,
"canbus": null
}
}

View File

@ -0,0 +1,30 @@
{
"location": {
"front": 12.375,
"left": 12.375
},
"absoluteEncoderOffset": 98.438,
"drive": {
"type": "sparkmax",
"id": 2,
"canbus": null
},
"angle": {
"type": "sparkmax",
"id": 3,
"canbus": null
},
"inverted": {
"angle": true,
"drive": false
},
"conversionFactor": {
"angle": 0,
"drive": 0
},
"encoder": {
"type": "cancoder",
"id": 4,
"canbus": null
}
}

View File

@ -0,0 +1,30 @@
{
"location": {
"front": 12.375,
"left": -12.375
},
"absoluteEncoderOffset": 17.227,
"drive": {
"type": "sparkmax",
"id": 17,
"canbus": null
},
"angle": {
"type": "sparkmax",
"id": 18,
"canbus": null
},
"inverted": {
"angle": true,
"drive": false
},
"conversionFactor": {
"angle": 0,
"drive": 0
},
"encoder": {
"type": "cancoder",
"id": 5,
"canbus": null
}
}

View File

@ -0,0 +1,16 @@
{
"optimalVoltage": 12,
"wheelGripCoefficientOfFriction": 1.19,
"currentLimit": {
"drive": 40,
"angle": 20
},
"conversionFactor": {
"angle": 16.8,
"drive": 0.04
},
"rampRate": {
"drive": 0.25,
"angle": 0.25
}
}

View File

@ -0,0 +1,16 @@
{
"drive": {
"p": 0.0020645,
"i": 0,
"d": 0,
"f": 0,
"iz": 0
},
"angle": {
"p": 0.0020645,
"i": 0,
"d": 0,
"f": 0,
"iz": 0
}
}

View File

@ -0,0 +1,14 @@
{
"imu": {
"type": "pigeon",
"id": 0,
"canbus": null
},
"invertedIMU": false,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}

View File

@ -6,17 +6,41 @@ package frc.robot;
/** Add your docs here. */
public class Constants {
//moteur
public static int lanceur = 1;
public static int lancer2 = 2;
public static int roue = 3;
public static int etoile = 4;
public static int Moteuracc2 = 5;
public static int Moteuracc = 6;
public static int guideur = 7;
// limit switsh
public static int guideurhaut = 8;
public static int guideurbas = 9;
public static int limitacc = 58;
// Lanceur
public static int lanceur = 10;
public static int lancer2 = 13;
public static int lancer3 = 14;
public static int lancer4 = 15;
// Ballayeuse
public static int roue = 16;
public static int etoile = 19;
// Accumulateur
public static int Moteuracc2 = 20;
public static int Moteuracc = 21;
// Guideur
public static int guideur = 22;
// Swerve
public static int AvantDroitDrive = 17;
public static int AvantDroitAngle = 18;
public static int AvantGaucheDrive = 2;
public static int AvantGaucheAngle = 3;
public static int ArriereDroitDrive = 11;
public static int ArriereDroitAngle = 12;
public static int ArriereGaucheDrive = 8;
public static int ArriereGaucheAngle = 9;
// CanCoder
public static int AvantDroit = 5;
public static int AvantGauche = 4;
public static int ArriereDroit = 6;
public static int ArriereGauche = 7;
// Limit switsh
public static int guideurhaut = 23;
public static int guideurbas = 24;
public static int limitacc = 25;
}

View File

@ -4,11 +4,40 @@
package frc.robot.subsystem;
import java.io.File;
import java.io.IOException;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import swervelib.SwerveDrive;
import swervelib.parser.SwerveParser;
public class Drive extends SubsystemBase {
/** Creates a new Drive. */
public Drive() {}
SwerveDrive swerveDrive;
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
public void drive(double x, double y, double zRotation){
swerveDrive.drive(new Translation2d(x*2, y*2), zRotation, true, false);
}
public Drive() {
try {
this.swerveDrive = new SwerveParser(swerveJsonDirectory).createSwerveDrive(2);
} catch (IOException e) {
e.printStackTrace();
}
}
public SwerveModulePosition[] distance(){
return swerveDrive.getModulePositions();
}
public void reset(){
}
@Override
public void periodic() {