From 26f86ef014be9da8eeb0c1cb078f45384b00b2ad Mon Sep 17 00:00:00 2001 From: Kenneth-Choothakan <134165881+Kenneth-Choothakan@users.noreply.github.com> Date: Fri, 1 Mar 2024 22:47:35 -0800 Subject: [PATCH] Added master and slave motor --- src/main/java/org/carlmontrobotics/subsystems/Arm.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/java/org/carlmontrobotics/subsystems/Arm.java b/src/main/java/org/carlmontrobotics/subsystems/Arm.java index f8292cfc..de170082 100644 --- a/src/main/java/org/carlmontrobotics/subsystems/Arm.java +++ b/src/main/java/org/carlmontrobotics/subsystems/Arm.java @@ -32,7 +32,7 @@ public class Arm extends SubsystemBase { // a boolean meant to tell if the arm is in a forbidden posistion AKA FORBIDDEN FLAG private static boolean forbFlag; private final CANSparkMax armMotor1 = MotorControllerFactory.createSparkMax(ARM_MOTOR_PORT_1, MotorConfig.NEO); - private final CANSparkMax armMotor2 = MotorControllerFactory.createSparkMax(ARM_MOTOR_PORT_2, MotorConfig.NEO) + private final CANSparkMax armMotor2 = MotorControllerFactory.createSparkMax(ARM_MOTOR_PORT_2, MotorConfig.NEO); private final RelativeEncoder armEncoder = armMotor1.getEncoder(); @@ -56,6 +56,8 @@ public Arm() { armEncoder.setPositionConversionFactor(rotationToRad); armEncoder.setVelocityConversionFactor(rotationToRad); armEncoder.setInverted(encoderInverted); + + armMotor2.follow(armMotor1); //armEncoder1.setZeroOffset(offsetRad);