Skip to content

Commit

Permalink
11/1/24 - Harshini
Browse files Browse the repository at this point in the history
drivebase is driving properly now and nothing is inverted!! (finally)
  • Loading branch information
TechnototesLaptop authored and kevinfrei committed Nov 2, 2024
1 parent e8d6746 commit 9dcd290
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.technototes.library.hardware.motor.EncodedMotor;
import com.technototes.library.hardware.sensor.IMU;
Expand Down Expand Up @@ -162,6 +163,7 @@ public DrivebaseSubsystem(
rl2 = rl;
rr2 = rr;
speed = DriveConstants.SLOW_MOTOR_SPEED;

}

public void fast() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,9 +89,8 @@ public void execute() {
// The math & signs looks wonky, because this makes things field-relative
// (Remember that "3 O'Clock" is zero degrees)
// We are making this change for the omni wheels on 20403
// We are making the orientation of the joystick's x negative to accommodate for the new direction of the wheels..
double yvalue = -y.getAsDouble();
double xvalue = -x.getAsDouble() *-1.0;
double xvalue = -x.getAsDouble();
if (straightDrive != null) {
if (straightDrive.getAsDouble() > TRIGGER_THRESHOLD) {
if (Math.abs(yvalue) > Math.abs(xvalue)) xvalue = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
import org.firstinspires.ftc.twenty403.controls.OperatorController;
import org.firstinspires.ftc.twenty403.helpers.StartingPosition;

@TeleOp(name = "Dual Driving")
@TeleOp(name = "Just Driving")
@SuppressWarnings("unused")
public class JustDrivingTeleOp extends CommandOpMode {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.technototes.library.hardware.motor.EncodedMotor;
import com.technototes.library.hardware.sensor.IMU;
Expand Down Expand Up @@ -178,6 +179,11 @@ public DrivebaseSubsystem(
// This is already handled in the parent class constructor (super)
// setLocalizer(l);
setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT);

fl.setDirection(DcMotorSimple.Direction.FORWARD);
rl.setDirection(DcMotorSimple.Direction.FORWARD);
rr.setDirection(DcMotorSimple.Direction.REVERSE);
fr.setDirection(DcMotorSimple.Direction.REVERSE);
}

@Override
Expand Down

0 comments on commit 9dcd290

Please sign in to comment.