Compare commits
8 Commits
Lanceur
...
ea96a16864
Author | SHA1 | Date | |
---|---|---|---|
ea96a16864 | |||
dfa05d79a7 | |||
650e8341ec | |||
025d9e47f0 | |||
f0cdb9a241 | |||
ae9e9577c2 | |||
89d155ae5e | |||
787251658c |
8
src/main/deploy/swerve/controllerproperties.json
Normal file
8
src/main/deploy/swerve/controllerproperties.json
Normal file
@ -0,0 +1,8 @@
|
|||||||
|
{
|
||||||
|
"angleJoystickRadiusDeadband": 0.5,
|
||||||
|
"heading": {
|
||||||
|
"p": 0.4,
|
||||||
|
"i": 0,
|
||||||
|
"d": 0.01
|
||||||
|
}
|
||||||
|
}
|
30
src/main/deploy/swerve/modules/backleft.json
Normal file
30
src/main/deploy/swerve/modules/backleft.json
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
{
|
||||||
|
"location": {
|
||||||
|
"front": -12.375,
|
||||||
|
"left": 12.375
|
||||||
|
},
|
||||||
|
"absoluteEncoderOffset":209.443,
|
||||||
|
"drive": {
|
||||||
|
"type": "talonFX",
|
||||||
|
"id": 8,
|
||||||
|
"canbus": null
|
||||||
|
},
|
||||||
|
"angle": {
|
||||||
|
"type": "talonFX",
|
||||||
|
"id": 9,
|
||||||
|
"canbus": null
|
||||||
|
},
|
||||||
|
"inverted": {
|
||||||
|
"angle": true,
|
||||||
|
"drive": false
|
||||||
|
},
|
||||||
|
"conversionFactor": {
|
||||||
|
"angle": 0,
|
||||||
|
"drive": 0
|
||||||
|
},
|
||||||
|
"encoder": {
|
||||||
|
"type": "cancoder",
|
||||||
|
"id": 6,
|
||||||
|
"canbus": null
|
||||||
|
}
|
||||||
|
}
|
30
src/main/deploy/swerve/modules/backright.json
Normal file
30
src/main/deploy/swerve/modules/backright.json
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
{
|
||||||
|
"location": {
|
||||||
|
"front": -12.375,
|
||||||
|
"left": -12.375
|
||||||
|
},
|
||||||
|
"absoluteEncoderOffset": 5.537,
|
||||||
|
"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": 7,
|
||||||
|
"canbus": null
|
||||||
|
}
|
||||||
|
}
|
30
src/main/deploy/swerve/modules/frontleft.json
Normal file
30
src/main/deploy/swerve/modules/frontleft.json
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
{
|
||||||
|
"location": {
|
||||||
|
"front": 12.375,
|
||||||
|
"left": 12.375
|
||||||
|
},
|
||||||
|
"absoluteEncoderOffset":258.223 ,
|
||||||
|
"drive": {
|
||||||
|
"type": "talonFX",
|
||||||
|
"id": 2,
|
||||||
|
"canbus": null
|
||||||
|
},
|
||||||
|
"angle": {
|
||||||
|
"type": "talonFX",
|
||||||
|
"id": 3,
|
||||||
|
"canbus": null
|
||||||
|
},
|
||||||
|
"inverted": {
|
||||||
|
"angle": true,
|
||||||
|
"drive": false
|
||||||
|
},
|
||||||
|
"conversionFactor": {
|
||||||
|
"angle": 0,
|
||||||
|
"drive": 0
|
||||||
|
},
|
||||||
|
"encoder": {
|
||||||
|
"type": "cancoder",
|
||||||
|
"id": 4,
|
||||||
|
"canbus": null
|
||||||
|
}
|
||||||
|
}
|
30
src/main/deploy/swerve/modules/frontright.json
Normal file
30
src/main/deploy/swerve/modules/frontright.json
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
{
|
||||||
|
"location": {
|
||||||
|
"front": 12.375,
|
||||||
|
"left": -12.375
|
||||||
|
},
|
||||||
|
"absoluteEncoderOffset": 110.215,
|
||||||
|
"drive": {
|
||||||
|
"type": "talonFX",
|
||||||
|
"id": 18,
|
||||||
|
"canbus": null
|
||||||
|
},
|
||||||
|
"angle": {
|
||||||
|
"type": "talonFX",
|
||||||
|
"id": 17,
|
||||||
|
"canbus": null
|
||||||
|
},
|
||||||
|
"inverted": {
|
||||||
|
"angle": true,
|
||||||
|
"drive": false
|
||||||
|
},
|
||||||
|
"conversionFactor": {
|
||||||
|
"angle": 0,
|
||||||
|
"drive": 0
|
||||||
|
},
|
||||||
|
"encoder": {
|
||||||
|
"type": "cancoder",
|
||||||
|
"id": 5,
|
||||||
|
"canbus": null
|
||||||
|
}
|
||||||
|
}
|
16
src/main/deploy/swerve/modules/physicalproperties.json
Normal file
16
src/main/deploy/swerve/modules/physicalproperties.json
Normal 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
|
||||||
|
}
|
||||||
|
}
|
16
src/main/deploy/swerve/modules/pidfproperties.json
Normal file
16
src/main/deploy/swerve/modules/pidfproperties.json
Normal file
@ -0,0 +1,16 @@
|
|||||||
|
{
|
||||||
|
"drive": {
|
||||||
|
"p": 0.0020645,
|
||||||
|
"i": 0,
|
||||||
|
"d": 0,
|
||||||
|
"f": 0,
|
||||||
|
"iz": 0
|
||||||
|
},
|
||||||
|
"angle": {
|
||||||
|
"p": 0.01,
|
||||||
|
"i": 0,
|
||||||
|
"d": 0,
|
||||||
|
"f": 0,
|
||||||
|
"iz": 0
|
||||||
|
}
|
||||||
|
}
|
14
src/main/deploy/swerve/swervedrive.json
Normal file
14
src/main/deploy/swerve/swervedrive.json
Normal file
@ -0,0 +1,14 @@
|
|||||||
|
{
|
||||||
|
"imu": {
|
||||||
|
"type": "pigeon",
|
||||||
|
"id": 0,
|
||||||
|
"canbus": null
|
||||||
|
},
|
||||||
|
"invertedIMU": false,
|
||||||
|
"modules": [
|
||||||
|
"frontleft.json",
|
||||||
|
"frontright.json",
|
||||||
|
"backleft.json",
|
||||||
|
"backright.json"
|
||||||
|
]
|
||||||
|
}
|
28
src/main/java/frc/robot/Subsystems/Accumulateur.java
Normal file
28
src/main/java/frc/robot/Subsystems/Accumulateur.java
Normal file
@ -0,0 +1,28 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot.Subsystems;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj.Encoder;
|
||||||
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||||
|
public class Accumulateur extends SubsystemBase {
|
||||||
|
|
||||||
|
/** Creates a new Accumulateur. */
|
||||||
|
public Accumulateur() {}
|
||||||
|
final WPI_TalonSRX accumulateur1 = new WPI_TalonSRX(0);
|
||||||
|
final WPI_TalonSRX accumulateur2 = new WPI_TalonSRX(10);
|
||||||
|
Encoder encoder = new Encoder(1,0);
|
||||||
|
public void encodeur(){
|
||||||
|
|
||||||
|
}
|
||||||
|
public void desaccumule(double vitesse){
|
||||||
|
accumulateur1.set(vitesse);
|
||||||
|
accumulateur2.set(-vitesse);
|
||||||
|
}
|
||||||
|
@Override
|
||||||
|
public void periodic() {
|
||||||
|
// This method will be called once per scheduler run
|
||||||
|
}
|
||||||
|
}
|
52
src/main/java/frc/robot/Subsystems/Drive.java
Normal file
52
src/main/java/frc/robot/Subsystems/Drive.java
Normal file
@ -0,0 +1,52 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot.Subsystems;
|
||||||
|
|
||||||
|
import java.io.File;
|
||||||
|
import java.io.IOException;
|
||||||
|
|
||||||
|
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||||
|
|
||||||
|
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 {
|
||||||
|
|
||||||
|
SwerveDrive swerveDrive;
|
||||||
|
|
||||||
|
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
|
||||||
|
|
||||||
|
Pigeon2 Gyro = new Pigeon2(0);
|
||||||
|
|
||||||
|
public void drive(double x, double y, double zRotation){
|
||||||
|
swerveDrive.drive(new Translation2d(x*5, y*5), zRotation*4, true, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
public Drive() {
|
||||||
|
try {
|
||||||
|
this.swerveDrive = new SwerveParser(swerveJsonDirectory).createSwerveDrive(5);
|
||||||
|
swerveDrive.setHeadingCorrection(true);
|
||||||
|
} catch (IOException e) {
|
||||||
|
e.printStackTrace();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
public void restgyroscope(){
|
||||||
|
Gyro.reset();
|
||||||
|
}
|
||||||
|
public SwerveModulePosition[] distance(){
|
||||||
|
return swerveDrive.getModulePositions();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void periodic() {
|
||||||
|
// This method will be called once per scheduler run
|
||||||
|
}
|
||||||
|
}
|
@ -7,10 +7,11 @@ package frc.robot.Subsystems;
|
|||||||
|
|
||||||
|
|
||||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||||
|
|
||||||
import com.revrobotics.CANSparkMax;
|
import com.revrobotics.CANSparkMax;
|
||||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj.Encoder;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class Lanceur extends SubsystemBase {
|
public class Lanceur extends SubsystemBase {
|
||||||
@ -20,6 +21,10 @@ public class Lanceur extends SubsystemBase {
|
|||||||
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(0);
|
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(0);
|
||||||
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(1);
|
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(1);
|
||||||
final CANSparkMax tourel = new CANSparkMax(2, MotorType.kBrushed);
|
final CANSparkMax tourel = new CANSparkMax(2, MotorType.kBrushed);
|
||||||
|
Encoder encoder = new Encoder(0, 1);
|
||||||
|
public void encodeur(double distance){
|
||||||
|
encoder.setDistancePerPulse(distance);
|
||||||
|
}
|
||||||
public void lance(double vitesse){
|
public void lance(double vitesse){
|
||||||
lanceur1.set(vitesse);
|
lanceur1.set(vitesse);
|
||||||
lanceur2.set(-vitesse);
|
lanceur2.set(-vitesse);
|
||||||
|
38
vendordeps/PathplannerLib.json
Normal file
38
vendordeps/PathplannerLib.json
Normal file
@ -0,0 +1,38 @@
|
|||||||
|
{
|
||||||
|
"fileName": "PathplannerLib.json",
|
||||||
|
"name": "PathplannerLib",
|
||||||
|
"version": "2024.2.8",
|
||||||
|
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
|
||||||
|
"frcYear": "2024",
|
||||||
|
"mavenUrls": [
|
||||||
|
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
|
||||||
|
],
|
||||||
|
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
|
||||||
|
"javaDependencies": [
|
||||||
|
{
|
||||||
|
"groupId": "com.pathplanner.lib",
|
||||||
|
"artifactId": "PathplannerLib-java",
|
||||||
|
"version": "2024.2.8"
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"jniDependencies": [],
|
||||||
|
"cppDependencies": [
|
||||||
|
{
|
||||||
|
"groupId": "com.pathplanner.lib",
|
||||||
|
"artifactId": "PathplannerLib-cpp",
|
||||||
|
"version": "2024.2.8",
|
||||||
|
"libName": "PathplannerLib",
|
||||||
|
"headerClassifier": "headers",
|
||||||
|
"sharedLibrary": false,
|
||||||
|
"skipInvalidPlatforms": true,
|
||||||
|
"binaryPlatforms": [
|
||||||
|
"windowsx86-64",
|
||||||
|
"linuxx86-64",
|
||||||
|
"osxuniversal",
|
||||||
|
"linuxathena",
|
||||||
|
"linuxarm32",
|
||||||
|
"linuxarm64"
|
||||||
|
]
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
Reference in New Issue
Block a user