Changes from 1/18 meeting and a bug fix that will probably invert controls again, but should resolve issues with robot oriented control
This commit is contained in:
parent
6f9f53011e
commit
385f606ed0
@ -9,9 +9,6 @@
|
||||
"Publishers": {
|
||||
"open": true
|
||||
},
|
||||
"Subscribers": {
|
||||
"open": true
|
||||
},
|
||||
"open": true
|
||||
},
|
||||
"retained": {
|
||||
|
@ -30,7 +30,7 @@ public class RobotContainer {
|
||||
private Drivetrain drivetrain;
|
||||
|
||||
private CommandXboxController primary;
|
||||
private CommandXboxController secondary;
|
||||
//private CommandXboxController secondary;
|
||||
|
||||
private Trigger isTeleopTrigger;
|
||||
|
||||
@ -58,7 +58,7 @@ public class RobotContainer {
|
||||
autoChooser = AutoBuilder.buildAutoChooser();
|
||||
|
||||
primary = new CommandXboxController(OIConstants.kPrimaryXboxUSB);
|
||||
secondary = new CommandXboxController(OIConstants.kSecondaryXboxUSB);
|
||||
//secondary = new CommandXboxController(OIConstants.kSecondaryXboxUSB);
|
||||
|
||||
isTeleopTrigger = new Trigger(DriverStation::isTeleopEnabled);
|
||||
|
||||
@ -89,8 +89,8 @@ public class RobotContainer {
|
||||
|
||||
drivetrain.setDefaultCommand(
|
||||
drivetrain.teleopCommand(
|
||||
primary::getLeftX,
|
||||
primary::getLeftY,
|
||||
primary::getLeftX,
|
||||
primary::getRightX,
|
||||
OIConstants.kTeleopDriveDeadband
|
||||
)
|
||||
@ -98,8 +98,8 @@ public class RobotContainer {
|
||||
|
||||
primary.povCenter().onFalse(
|
||||
drivetrain.driveCardinal(
|
||||
primary::getLeftX,
|
||||
primary::getLeftY,
|
||||
primary::getLeftX,
|
||||
primary.getHID()::getPOV,
|
||||
OIConstants.kTeleopDriveDeadband).until(
|
||||
() -> MathUtil.applyDeadband(primary.getRightX(), OIConstants.kTeleopDriveDeadband) != 0
|
||||
@ -109,8 +109,8 @@ public class RobotContainer {
|
||||
// Lock on to the appropriate Amp AprilTag while still being able to strafe and drive forward and back
|
||||
primary.a().onTrue(
|
||||
drivetrain.driveAprilTagLock(
|
||||
primary::getLeftX,
|
||||
primary::getLeftY,
|
||||
primary::getLeftX,
|
||||
OIConstants.kTeleopDriveDeadband,
|
||||
ampTagID
|
||||
).until(
|
||||
@ -121,8 +121,8 @@ public class RobotContainer {
|
||||
// Lock on to the appropriate Source AprilTag while still being able to strafe and drive forward and back
|
||||
primary.b().onTrue(
|
||||
drivetrain.driveAprilTagLock(
|
||||
primary::getLeftX,
|
||||
primary::getLeftY,
|
||||
primary::getLeftX,
|
||||
OIConstants.kTeleopDriveDeadband,
|
||||
sourceTagID
|
||||
).until(
|
||||
@ -133,8 +133,8 @@ public class RobotContainer {
|
||||
// Lock on to the appropriate Speaker AprilTag while still being able to strafe and drive forward and back
|
||||
primary.x().onTrue(
|
||||
drivetrain.driveAprilTagLock(
|
||||
primary::getLeftX,
|
||||
primary::getLeftY,
|
||||
primary::getLeftX,
|
||||
OIConstants.kTeleopDriveDeadband,
|
||||
speakerTag
|
||||
).until(
|
||||
|
@ -20,12 +20,11 @@ public final class AutoConstants {
|
||||
public static final double kPHeadingController = 0.02; // for heading control NOT PATHING
|
||||
public static final double kDHeadingController = 0.0025;
|
||||
|
||||
// TODO Is the robot module radius correct?
|
||||
public static final HolonomicPathFollowerConfig kPFConfig = new HolonomicPathFollowerConfig(
|
||||
new PIDConstants(kPXController),
|
||||
new PIDConstants(kPThetaController),
|
||||
kMaxSpeedMetersPerSecond,
|
||||
Units.inchesToMeters(36.77),
|
||||
Units.inchesToMeters(34.65),
|
||||
new ReplanningConfig()
|
||||
);
|
||||
|
||||
|
@ -15,11 +15,9 @@ public final class DrivetrainConstants {
|
||||
public static final double kRotationalSlewRate = 4.0; // percent per second (1 = 100%)
|
||||
|
||||
// Chassis configuration
|
||||
// TODO Update track width
|
||||
public static final double kTrackWidth = Units.inchesToMeters(26.5-1.75*2);
|
||||
public static final double kTrackWidth = Units.inchesToMeters(28-1.75*2);
|
||||
// Distance between centers of right and left wheels on robot
|
||||
// TODO Update wheel base
|
||||
public static final double kWheelBase = Units.inchesToMeters(32.3-1.75*2);
|
||||
public static final double kWheelBase = Units.inchesToMeters(28-1.75*2);
|
||||
// Distance between front and back wheels on robot
|
||||
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
|
||||
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
|
||||
@ -36,12 +34,12 @@ public final class DrivetrainConstants {
|
||||
// SPARK MAX CAN IDs
|
||||
public static final int kFrontLeftDrivingCanId = 8;
|
||||
public static final int kRearLeftDrivingCanId = 3;
|
||||
public static final int kFrontRightDrivingCanId = 2;
|
||||
public static final int kFrontRightDrivingCanId = 6;
|
||||
public static final int kRearRightDrivingCanId = 1;
|
||||
|
||||
public static final int kFrontLeftTurningCanId = 4;
|
||||
public static final int kRearLeftTurningCanId = 7;
|
||||
public static final int kFrontRightTurningCanId = 6;
|
||||
public static final int kFrontRightTurningCanId = 2;
|
||||
public static final int kRearRightTurningCanId = 5;
|
||||
|
||||
public static final double kTurnToleranceDeg = 0;
|
||||
@ -49,6 +47,5 @@ public final class DrivetrainConstants {
|
||||
|
||||
public static final boolean kGyroReversed = true;
|
||||
|
||||
// TODO Is this offset going to continue to be correct for this year
|
||||
public static final double kRobotStartOffset = 180;
|
||||
public static final double kRobotStartOffset = 0;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user