Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
commit
8962660b60
@ -1,10 +1,5 @@
|
||||
{
|
||||
"HALProvider": {
|
||||
"DIO": {
|
||||
"window": {
|
||||
"visible": true
|
||||
}
|
||||
},
|
||||
"Other Devices": {
|
||||
"SPARK MAX [10]": {
|
||||
"header": {
|
||||
@ -27,11 +22,14 @@
|
||||
}
|
||||
}
|
||||
},
|
||||
<<<<<<< HEAD
|
||||
"Solenoids": {
|
||||
"window": {
|
||||
"visible": true
|
||||
}
|
||||
},
|
||||
=======
|
||||
>>>>>>> 88c4a9552f1a0b19d806a7672f738c1a9b60846b
|
||||
"Timing": {
|
||||
"window": {
|
||||
"visible": false
|
||||
|
@ -3,7 +3,7 @@
|
||||
"front": -12.375,
|
||||
"left": 12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 80.332,
|
||||
"absoluteEncoderOffset": 299.443,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 8,
|
||||
@ -24,7 +24,7 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 7,
|
||||
"id": 6,
|
||||
"canbus": null
|
||||
}
|
||||
}
|
@ -3,7 +3,7 @@
|
||||
"front": -12.375,
|
||||
"left": -12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 28.74,
|
||||
"absoluteEncoderOffset": 95.537,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 11,
|
||||
@ -24,7 +24,7 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 6,
|
||||
"id": 7,
|
||||
"canbus": null
|
||||
}
|
||||
}
|
@ -3,7 +3,7 @@
|
||||
"front": 12.375,
|
||||
"left": 12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 98.438,
|
||||
"absoluteEncoderOffset": 348.223 ,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 2,
|
||||
|
@ -3,15 +3,15 @@
|
||||
"front": 12.375,
|
||||
"left": -12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 17.227,
|
||||
"absoluteEncoderOffset": 200.215,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 17,
|
||||
"id": 18,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "sparkmax",
|
||||
"id": 18,
|
||||
"id": 17,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
|
@ -27,8 +27,8 @@ public class Constants {
|
||||
public static int grimpeurg = 27;
|
||||
|
||||
// Swerve
|
||||
public static int AvantDroitDrive = 17;
|
||||
public static int AvantDroitAngle = 18;
|
||||
public static int AvantDroitDrive = 18;
|
||||
public static int AvantDroitAngle = 17;
|
||||
public static int AvantGaucheDrive = 2;
|
||||
public static int AvantGaucheAngle = 3;
|
||||
public static int ArriereDroitDrive = 11;
|
||||
|
@ -87,7 +87,7 @@ public class RobotContainer {
|
||||
// deplacement
|
||||
configureBindings();
|
||||
drive.setDefaultCommand(new RunCommand(()->{
|
||||
drive.drive(-MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(-joystick.getX(),0.2), MathUtil.applyDeadband(-joystick.getZ(), 0.2));
|
||||
drive.drive(MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(joystick.getX(),0.2), MathUtil.applyDeadband(joystick.getZ(), 0.2));
|
||||
},drive));
|
||||
|
||||
// grimpeur manuel
|
||||
|
@ -12,8 +12,6 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.Constants;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||
|
||||
public class Accumulateur extends SubsystemBase {
|
||||
/** Creates a new Accumulateur. */
|
||||
|
@ -6,7 +6,6 @@ package frc.robot.subsystem;
|
||||
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.Constants;
|
||||
|
||||
|
@ -6,12 +6,10 @@ package frc.robot.subsystem;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
|
||||
import com.pathplanner.lib.auto.AutoBuilder;
|
||||
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
|
||||
import com.pathplanner.lib.util.PIDConstants;
|
||||
import com.pathplanner.lib.util.ReplanningConfig;
|
||||
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
|
@ -7,9 +7,6 @@ package frc.robot.subsystem;
|
||||
import com.kauailabs.navx.frc.AHRS;
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.Solenoid;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
|
@ -5,7 +5,6 @@
|
||||
package frc.robot.subsystem;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||
|
@ -6,7 +6,6 @@ package frc.robot.subsystem;
|
||||
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
|
@ -4,7 +4,6 @@
|
||||
|
||||
package frc.robot.subsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
|
Loading…
x
Reference in New Issue
Block a user