Skip to content

Commit

Permalink
Update Drivetrain from VictorSP to CANTalonSRX
Browse files Browse the repository at this point in the history
  • Loading branch information
babbitt committed Feb 16, 2018
1 parent ace624f commit 40413d4
Show file tree
Hide file tree
Showing 4 changed files with 37 additions and 15 deletions.
3 changes: 2 additions & 1 deletion .classpath
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<classpathentry kind="var" path="cscore" sourcepath="cscore.sources"/>
<classpathentry kind="var" path="wpiutil" sourcepath="wpiutil.sources"/>
<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER/org.eclipse.jdt.internal.debug.ui.launcher.StandardVMType/JavaSE-1.8"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRLib.jar"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRE_Phoenix-sources.jar"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRE_Phoenix.jar"/>
<classpathentry kind="output" path="bin"/>
</classpath>
1 change: 0 additions & 1 deletion bin/.gitignore

This file was deleted.

12 changes: 8 additions & 4 deletions src/org/usfirst/frc/team334/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,14 @@ public class Constants {
public static final int ELEVATOR_TO_EXCHANGE_BUTTON = 4;
public static final int COLLAPSE_ELEVATOR_BUTTON = 5;

// Motors
public static final int DRIVETRAIN_LEFT = 0;
public static final int DRIVETRAIN_RIGHT = 1;

// DriveTrain
public static final int DRIVETRAIN_MC_L = 5;
public static final int DRIVETRAIN_C1_L = 3;
public static final int DRIVETRAIN_C2_L = 4;
public static final int DRIVETRAIN_MC_R = 0;
public static final int DRIVETRAIN_C1_R = 1;
public static final int DRIVETRAIN_C2_R = 2;

// Pancake Solenoids - Drivetrain
public static final int PANCAKE_L_INPUT = 0;
public static final int PANCAKE_L_OUTPUT = 1;
Expand Down
36 changes: 27 additions & 9 deletions src/org/usfirst/frc/team334/robot/subsystems/Drive.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,14 @@
package org.usfirst.frc.team334.robot.subsystems;

import java.util.ArrayList;

import org.usfirst.frc.team334.robot.Constants;
import org.usfirst.frc.team334.robot.pids.BNO055;

import com.ctre.phoenix.motorcontrol.can.TalonSRX;

import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Ultrasonic;
import edu.wpi.first.wpilibj.VictorSP;
import edu.wpi.first.wpilibj.command.Subsystem;

/**
Expand All @@ -31,13 +34,24 @@ public enum DriveControlState {
public static Ultrasonic rUltrasonicL = new Ultrasonic(Constants.ULTRASONIC_R_DRIVETRAIN_PING, Constants.ULTRASONIC_R_DRIVETRAIN_ECHO);
public static BNO055 rGyro = BNO055.getInstance(BNO055.opmode_t.OPERATION_MODE_IMUPLUS, BNO055.vector_type_t.VECTOR_EULER);

private VictorSP left;
private VictorSP right;
private TalonSRX miniCimL,miniCimR,cim1L,cim2L,cim1R,cim2R;

ArrayList<TalonSRX> left,right;

public Drive() {
left = new VictorSP(Constants.DRIVETRAIN_LEFT);
right = new VictorSP(Constants.DRIVETRAIN_RIGHT);
right.setInverted(true);
miniCimL = new TalonSRX(Constants.DRIVETRAIN_MC_L);
cim1L = new TalonSRX(Constants.DRIVETRAIN_C1_L);
cim2L = new TalonSRX(Constants.DRIVETRAIN_C2_L);
miniCimR = new TalonSRX(Constants.DRIVETRAIN_MC_R);
cim1R = new TalonSRX(Constants.DRIVETRAIN_C1_R);
cim2R = new TalonSRX(Constants.DRIVETRAIN_C2_R);

left.add(miniCimL);
left.add(cim1L);
left.add(cim2L);
right.add(miniCimR);
right.add(cim1R);
right.add(cim2R);
}

public void stop() {
Expand All @@ -46,15 +60,19 @@ public void stop() {
}

public void setLeft(double speed) {
left.set(speed);
for(TalonSRX TSRX : left) {
TSRX.set(com.ctre.phoenix.motorcontrol.ControlMode.Current, speed);
}
}

public void setRight(double speed) {
right.set(speed);
for(TalonSRX TSRX : right) {
TSRX.set(com.ctre.phoenix.motorcontrol.ControlMode.Current, speed);
}
}

public void initDefaultCommand() {

}

}
}

0 comments on commit 40413d4

Please sign in to comment.