working on dt offsets
This commit is contained in:
parent
aff9a4f2cb
commit
f0b7955faa
@ -196,6 +196,9 @@ public class RobotContainer {
|
||||
.withPosition(4, 1)
|
||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||
|
||||
sensorTab.addDouble("gyro angle", drivetrain::getGyroValue);
|
||||
|
||||
|
||||
/*
|
||||
sensorTab.addBoolean("Algae Sensor", manipulator::getAlgaePhotoSwitch)
|
||||
.withSize(1, 1)
|
||||
|
@ -3,7 +3,7 @@ package frc.robot.constants;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
|
||||
public class ClimberPivotConstants {
|
||||
public static final int kPivotMotorID = 0;
|
||||
public static final int kPivotMotorID = 10;
|
||||
|
||||
public static final int kClimberLimitSwitchID = 0;
|
||||
|
||||
|
@ -3,7 +3,7 @@ package frc.robot.constants;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
|
||||
public class ClimberRollersConstants {
|
||||
public static final int kRollerMotorID = 0;
|
||||
public static final int kRollerMotorID = 9;
|
||||
|
||||
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
|
||||
}
|
||||
|
@ -38,15 +38,15 @@ public class DrivetrainConstants {
|
||||
public static final double kSysIDTurningTimeout = 10;
|
||||
|
||||
// SPARK MAX CAN IDs
|
||||
public static final int kFrontLeftDrivingCanId = 11;
|
||||
public static final int kRearLeftDrivingCanId = 13;
|
||||
public static final int kFrontRightDrivingCanId = 15;
|
||||
public static final int kRearRightDrivingCanId = 17;
|
||||
public static final int kFrontLeftDrivingCanId = 0;
|
||||
public static final int kRearLeftDrivingCanId = 2;
|
||||
public static final int kFrontRightDrivingCanId = 1;
|
||||
public static final int kRearRightDrivingCanId = 3;
|
||||
|
||||
public static final int kFrontLeftTurningCanId = 10;
|
||||
public static final int kRearLeftTurningCanId = 12;
|
||||
public static final int kFrontRightTurningCanId = 14;
|
||||
public static final int kRearRightTurningCanId = 16;
|
||||
public static final int kFrontLeftTurningCanId = 2;
|
||||
public static final int kRearLeftTurningCanId = 4;
|
||||
public static final int kFrontRightTurningCanId = 7;
|
||||
public static final int kRearRightTurningCanId = 5;
|
||||
|
||||
public static final boolean kGyroReversed = true;
|
||||
|
||||
|
@ -11,13 +11,13 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
|
||||
|
||||
public class ElevatorConstants {
|
||||
public static final int kElevatorMotor1ID = 0;
|
||||
public static final int kElevatorMotor2ID = 0;
|
||||
public static final int kElevatorMotor1ID = 8;
|
||||
public static final int kElevatorMotor2ID = 6;
|
||||
|
||||
public static final int kBottomLimitSwitchID = 0;
|
||||
|
||||
// 60/11 gearing multiplied by circumference of sprocket multiplied by 2 for carriage position
|
||||
public static final double kEncoderConversionFactor = 11/60 * (22*0.25) * 2;
|
||||
public static final double kEncoderConversionFactor = 11.0/60.0 * (22.0*0.25) * 2.0;
|
||||
|
||||
public static final int kCurrentLimit = 40;
|
||||
|
||||
@ -75,8 +75,7 @@ public class ElevatorConstants {
|
||||
.smartCurrentLimit(kCurrentLimit)
|
||||
.idleMode(kIdleMode);
|
||||
motorConfig.encoder
|
||||
.positionConversionFactor(kEncoderConversionFactor)
|
||||
.velocityConversionFactor(kEncoderConversionFactor / 60.0);
|
||||
.positionConversionFactor(kEncoderConversionFactor);
|
||||
motorConfig.closedLoop
|
||||
.p(kPositionControllerP)
|
||||
.i(kPositionControllerI)
|
||||
|
@ -3,9 +3,9 @@ package frc.robot.constants;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
|
||||
public class ManipulatorConstants {
|
||||
public static final int kManipulatorMotorID = 0;
|
||||
public static final int kCoralBeamBreakID = 0;
|
||||
public static final int kAlgaeBeamBreakID = 0;
|
||||
public static final int kManipulatorMotorID = 12;
|
||||
public static final int kCoralBeamBreakID = 1;
|
||||
public static final int kAlgaeBeamBreakID = 2;
|
||||
|
||||
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
|
||||
}
|
||||
|
@ -13,11 +13,11 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
|
||||
|
||||
public class ManipulatorPivotConstants {
|
||||
public static final int kArmMotorID = 0;
|
||||
public static final int kArmMotorID = 1;
|
||||
|
||||
public static final int kMotorCurrentMax = 40;
|
||||
|
||||
public static final double kPivotConversion = 12/60 * 20/60 * 12/28;
|
||||
public static final double kPivotConversion = 12.0/60.0 * 20.0/60.0 * 12.0/28.0;
|
||||
|
||||
public static final double kPivotMaxVelocity = 0;
|
||||
|
||||
|
@ -16,7 +16,7 @@ public class ClimberPivot extends SubsystemBase {
|
||||
|
||||
private RelativeEncoder neoEncoder;
|
||||
|
||||
private DigitalInput cageLimitSwitch;
|
||||
//private DigitalInput cageLimitSwitch;
|
||||
|
||||
public ClimberPivot() {
|
||||
pivotMotor = new SparkMax(
|
||||
@ -32,7 +32,7 @@ public class ClimberPivot extends SubsystemBase {
|
||||
|
||||
neoEncoder = pivotMotor.getEncoder();
|
||||
|
||||
cageLimitSwitch = new DigitalInput(ClimberPivotConstants.kClimberLimitSwitchID);
|
||||
//cageLimitSwitch = new DigitalInput(ClimberPivotConstants.kClimberLimitSwitchID);
|
||||
}
|
||||
|
||||
public Command runPivot(double speed) {
|
||||
@ -59,9 +59,9 @@ public class ClimberPivot extends SubsystemBase {
|
||||
*
|
||||
* @return Is the cage in the climber
|
||||
*/
|
||||
public boolean getCageLimitSwitch() {
|
||||
return cageLimitSwitch.get();
|
||||
}
|
||||
// public boolean getCageLimitSwitch() {
|
||||
// return cageLimitSwitch.get();
|
||||
//}
|
||||
|
||||
public double getEncoderPosition() {
|
||||
return neoEncoder.getPosition();
|
||||
|
@ -228,7 +228,7 @@ public class Drivetrain extends SubsystemBase {
|
||||
|
||||
/** Zeroes the heading of the robot. */
|
||||
public void zeroHeading() {
|
||||
ahrs.reset();;
|
||||
ahrs.reset();
|
||||
}
|
||||
|
||||
public double getGyroValue() {
|
||||
|
@ -42,7 +42,8 @@ public class Manipulator extends SubsystemBase {
|
||||
*/
|
||||
public Command defaultCommand() {
|
||||
return run(() -> {
|
||||
runUntilCollected(0.1);
|
||||
//runUntilCollected(0.1);
|
||||
manipulatorMotor.set(0);
|
||||
});
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user