Skip to content

Commit

Permalink
Fix robot wheels moving in opposite direction (#17)
Browse files Browse the repository at this point in the history
  • Loading branch information
team6101 authored Feb 19, 2024
1 parent 8e31961 commit 12ce167
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 8 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@ public class Constants {

/*DRIVE TRAIN MOTOR IDs*/
public static final int DRIVE_LEFT_PARENT_ID = 4;
public static final int DRIVE_LEFT_CHILD_ID = 5;
public static final int DRIVE_RIGHT_PARENT_ID = 2;
public static final int DRIVE_LEFT_CHILD_ID = 8;
public static final int DRIVE_RIGHT_PARENT_ID = 11;
public static final int DRIVE_RIGHT_CHILD_ID = 3;

/*CONTROLLER PORT IDs*/
Expand Down
9 changes: 6 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,12 @@ public static AHRS getGyroscope() {
public void robotInit() {
aprilTagHighlighter = new AprilTagHighlighter();
autonRouteChooser.addOption("move forward", "move forward");
autonRouteChooser.addOption("move backwards", "move backwards");
SmartDashboard.putData(autonRouteChooser);

// driveRightChild.setInverted(true);
driveLeftParent.setInverted(true);
driveRightParent.setInverted(false);

driveRightParent.setInverted(true);
driveLeftChild.follow(driveLeftParent);
driveRightChild.follow(driveRightParent);

Expand Down Expand Up @@ -175,11 +177,12 @@ public void teleopPeriodic() {
double leftY = driverController.getLeftY();
double rightY = driverController.getRightY();
// TODO the left wheels were moving despite the controller output being 0, why?
QuickActions.stopAll();
if (Math.abs(leftY) > .03) {
driveLeftParent.set(-leftY);
}
if (Math.abs(rightY) > .03) {
driveRightParent.set(-rightY);
driveRightParent.set(rightY);
}
driverController.setRumble(RumbleType.kBothRumble, 0.1);

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotMotors.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
public class RobotMotors {

public static void setupMotors(MotorController leftMotor, MotorController rightMotor) {
leftMotor.setInverted(true);
rightMotor.setInverted(false);
// leftMotor.setInverted(true);
// rightMotor.setInverted(false);
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/motor/SparkMotorController.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ public class SparkMotorController implements MotorController {

SparkMotorController(int canID) {
controller = new CANSparkMax(canID, MotorType.kBrushless);
encoder = controller.getEncoder(SparkRelativeEncoder.Type.kQuadrature, 42);
encoder = controller.getEncoder(SparkRelativeEncoder.Type.kHallSensor, 42);

// number
// of ticks
Expand Down

0 comments on commit 12ce167

Please sign in to comment.