Merge branch 'master' of https://git.demerso.net/pls5618/2024/betabot-2024
This commit is contained in:
commit
c6ccc37f2d
23
simgui.json
23
simgui.json
@ -7,6 +7,29 @@
|
||||
},
|
||||
"windows": {
|
||||
"/SmartDashboard/Field": {
|
||||
"Robot": {
|
||||
"arrowColor": [
|
||||
1.0,
|
||||
1.0,
|
||||
1.0,
|
||||
255.0
|
||||
],
|
||||
"color": [
|
||||
1.0,
|
||||
1.0,
|
||||
1.0,
|
||||
255.0
|
||||
],
|
||||
"style": "Box/Image"
|
||||
},
|
||||
"XModules": {
|
||||
"arrowColor": [
|
||||
0.0,
|
||||
1.0,
|
||||
0.0,
|
||||
255.0
|
||||
]
|
||||
},
|
||||
"window": {
|
||||
"visible": true
|
||||
}
|
||||
|
@ -1,5 +1,5 @@
|
||||
{
|
||||
"angleJoystickRadiusDeadband": 0.5,
|
||||
"angleJoystickRadiusDeadband": 0.6,
|
||||
"heading": {
|
||||
"p": 0.4,
|
||||
"i": 0,
|
||||
|
@ -3,7 +3,7 @@
|
||||
"front": -12.375,
|
||||
"left": 12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 0,
|
||||
"absoluteEncoderOffset": 80.332,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 8,
|
||||
@ -16,11 +16,11 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 22,
|
||||
"id": 7,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -3,7 +3,7 @@
|
||||
"front": -12.375,
|
||||
"left": -12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 0,
|
||||
"absoluteEncoderOffset": 28.740 ,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 11,
|
||||
@ -16,11 +16,11 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 22,
|
||||
"id": 6,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -3,7 +3,7 @@
|
||||
"front": 12.375,
|
||||
"left": 12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 0,
|
||||
"absoluteEncoderOffset": 98.438,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 2,
|
||||
@ -16,11 +16,11 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 22,
|
||||
"id": 4,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -3,7 +3,7 @@
|
||||
"front": 12.375,
|
||||
"left": -12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 0,
|
||||
"absoluteEncoderOffset": 17.227,
|
||||
"drive": {
|
||||
"type": "sparkmax",
|
||||
"id": 17,
|
||||
@ -16,11 +16,11 @@
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 22,
|
||||
"id": 5,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"drive": false,
|
||||
"angle": false
|
||||
"angle": true
|
||||
}
|
||||
}
|
@ -7,7 +7,7 @@
|
||||
"iz": 0
|
||||
},
|
||||
"angle": {
|
||||
"p": 0.0020645,
|
||||
"p": 0.005,
|
||||
"i": 0,
|
||||
"d": 0,
|
||||
"f": 0,
|
||||
|
@ -3,18 +3,15 @@ package frc.robot;
|
||||
public class Constants {
|
||||
|
||||
//Moteur
|
||||
public static int lanceur = 0;
|
||||
public static int lanceur = 10;
|
||||
public static int avantdroitDrive = 17;
|
||||
public static int avantdroitAngle = 18;
|
||||
public static int avantgaucheDrive = 0;
|
||||
public static int avantgaucheAngle = 1;
|
||||
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;
|
||||
public static int accumulateur = 9;
|
||||
|
||||
//limit switch
|
||||
public static int ballon = 10;
|
||||
public static int accumulateur = 19;
|
||||
|
||||
}
|
||||
|
@ -3,8 +3,8 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||
@ -14,7 +14,6 @@ import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
import frc.robot.commands.Avancer;
|
||||
import frc.robot.commands.Force1;
|
||||
import frc.robot.commands.Force2;
|
||||
@ -45,6 +44,7 @@ public class RobotContainer {
|
||||
GenericEntry force5 = forces.add("Force5", 0).getEntry();
|
||||
GenericEntry force6 = forces.add("Force6", 0).getEntry();
|
||||
GenericEntry force7 = forces.add("Force7", 0).getEntry();
|
||||
|
||||
CommandXboxController manette = new CommandXboxController(0);
|
||||
CommandJoystick joystick1 = new CommandJoystick(0);
|
||||
Drive drive = new Drive();
|
||||
@ -52,7 +52,7 @@ public class RobotContainer {
|
||||
|
||||
configureBindings();
|
||||
drive.setDefaultCommand(new RunCommand(()->{
|
||||
drive.drive(joystick1.getX(), -joystick1.getY(), -joystick1.getZ());
|
||||
drive.drive(-joystick1.getY(), -joystick1.getX(), MathUtil.applyDeadband(-joystick1.getZ(), 0.2));
|
||||
},drive));
|
||||
}
|
||||
|
||||
|
@ -35,6 +35,6 @@ public class Avancer extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return drive.distance()[0].distanceMeters>1;
|
||||
}
|
||||
}
|
||||
|
@ -33,6 +33,6 @@ public class Reculer extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return drive.distance()[0].distanceMeters>1;
|
||||
}
|
||||
}
|
||||
|
@ -19,7 +19,7 @@ public class Drive extends SubsystemBase {
|
||||
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
|
||||
|
||||
public void drive(double x, double y, double zRotation){
|
||||
swerveDrive.drive(new Translation2d(x, y), zRotation, true, false);
|
||||
swerveDrive.drive(new Translation2d(x, y), zRotation, false, false);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user