Completed
Push — master ( 0672dd...74c8db )
by John
33s
created

goToMiddle()   B

Complexity

Conditions 5

Size

Total Lines 25

Duplication

Lines 0
Ratio 0 %

Importance

Changes 0
Metric Value
c 0
b 0
f 0
dl 0
loc 25
rs 8.8133
cc 5
1
package org.usfirst.frc.team3695.robot.subsystems;
2
3
import org.usfirst.frc.team3695.robot.Constants;
4
import org.usfirst.frc.team3695.robot.commands.ManualCommandDrive;
5
import org.usfirst.frc.team3695.robot.commands.ManualCommandGrow;
6
import org.usfirst.frc.team3695.robot.enumeration.Position;
7
import org.usfirst.frc.team3695.robot.util.Util;
8
import org.usfirst.frc.team3695.robot.util.Xbox;
9
10
import com.ctre.CANTalon;
11
import com.ctre.phoenix.motorcontrol.ControlMode;
12
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
13
14
import edu.wpi.first.wpilibj.DigitalInput;
15
import edu.wpi.first.wpilibj.Joystick;
16
import edu.wpi.first.wpilibj.command.Subsystem;
17
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
18
19
/** the big, metal pole */
20
public class SubsystemMast extends Subsystem {
21
	
22
	
23
	private TalonSRX leftPinion;
24
	private TalonSRX rightPinion;
25
	private TalonSRX screw;
26
	
27
	DigitalInput lowerPinionLimit;
28
    DigitalInput upperPinionLimit;
29
    DigitalInput lowerScrewLimit;
30
    DigitalInput midScrewLimit;
31
    DigitalInput upperScrewLimit;
32
    
33
    private Position carriagePosition;
34
    private Boolean midIsPressed;
0 ignored issues
show
Unused Code introduced by
Consider removing the unused private field midIsPressed.
Loading history...
35
36
	
37
	/** runs at robot boot */
38
    public void initDefaultCommand() {
39
    	setDefaultCommand(new ManualCommandGrow()); }
40
	
41
	/** gives birth to the CANTalons */
42
    public SubsystemMast(){
43
    	lowerPinionLimit = new DigitalInput(1);
44
        upperPinionLimit = new DigitalInput(2);
0 ignored issues
show
Comprehensibility introduced by
Consider assigning this magic number 2 to a constant.

Using constants for hard-coded numbers is a best practice. A constant’s name can explain the rationale behind this magic number. It is also easier to find if you ever need to change it.

Loading history...
45
        lowerScrewLimit  = new DigitalInput(3);
0 ignored issues
show
Comprehensibility introduced by
Consider assigning this magic number 3 to a constant.

Using constants for hard-coded numbers is a best practice. A constant’s name can explain the rationale behind this magic number. It is also easier to find if you ever need to change it.

Loading history...
46
        midScrewLimit    = new DigitalInput(4);
0 ignored issues
show
Comprehensibility introduced by
Consider assigning this magic number 4 to a constant.

Using constants for hard-coded numbers is a best practice. A constant’s name can explain the rationale behind this magic number. It is also easier to find if you ever need to change it.

Loading history...
47
        upperScrewLimit  = new DigitalInput(5);
0 ignored issues
show
Comprehensibility introduced by
Consider assigning this magic number 5 to a constant.

Using constants for hard-coded numbers is a best practice. A constant’s name can explain the rationale behind this magic number. It is also easier to find if you ever need to change it.

Loading history...
48
    	
49
    	leftPinion = new TalonSRX(Constants.LEFT_PINION_MOTOR);
50
    	rightPinion = new TalonSRX(Constants.RIGHT_PINION_MOTOR);
51
    	screw = new TalonSRX(Constants.SCREW_MOTOR);
52
    		voltage(leftPinion);
53
    		voltage(rightPinion);
54
    		voltage(screw);
55
    }
56
57
   	
58
   	/** apply pinion motor invert */
59
   	public static final double leftPinionate(double left) {
60
   		return left * (Constants.LEFT_PINION_MOTOR_INVERT ? -1.0 : 1.0);
61
   	}
62
   	
63
   	/** apply screw motor invert */
64
   	public static final double rightPinionate(double right) {
65
   		return right * (Constants.RIGHT_PINION_MOTOR_INVERT ? -1.0 : 1.0);
66
   	}
67
   	
68
   	public static final double screwify(double screw) {
69
   		return screw * (Constants.SCREW_MOTOR_INVERT ? -1.0 : 1.0);
70
   	}
71
    
72
   	/** raise the mast at RT-LR trigger speed */
73
    public void moveBySpeed(Joystick joy, double inhibitor) {
74
    	double screwSpeed = Xbox.RIGHT_Y(joy);
75
    	double pinionSpeed = Xbox.LEFT_Y(joy);
76
    	
77
//		if (lowerPinionLimit.get() && pinionSpeed < 0)   { pinionSpeed = 0; }
78
//		if (upperPinionLimit.get() && pinionSpeed > 1)   { pinionSpeed = 0; }
79
//		if (lowerScrewLimit.get()  && screwSpeed  < 0)   { screwSpeed = 0;  }
80
//		if (upperScrewLimit.get()  && screwSpeed  > 1)   { screwSpeed = 0;  }
81
			
82
//			updateCarriage();
83
    	publishSwitches();
84
    	leftPinion.set(ControlMode.PercentOutput, leftPinionate(pinionSpeed));
85
    	rightPinion.set(ControlMode.PercentOutput, rightPinionate(pinionSpeed));
86
    	screw.set(ControlMode.PercentOutput, inhibitor * screwify(screwSpeed));
87
    }
88
    
89
    public void setCarriagePosition(Position position) {
90
    	carriagePosition = position;
91
    }
92
    
93
    public void updateCarriage() {
94
    	if (midScrewLimit.get()) {
95
    		carriagePosition = Position.CENTER;
96
    	}
97
    	else if (carriagePosition == Position.CENTER && !midScrewLimit.get()) {
98
    		if (screw.getMotorOutputPercent() > 0) {
99
    			carriagePosition = Position.UP;
100
    		} else if (screw.getMotorOutputPercent() < 0) {
101
    			carriagePosition = Position.DOWN;
102
    		}
103
    	}
104
    }
105
    	
106
    public void publishSwitches() {
107
    	SmartDashboard.putBoolean("Lower Screw", lowerScrewLimit.get());
108
    	SmartDashboard.putBoolean("Mid Position", midScrewLimit.get());
109
    	SmartDashboard.putBoolean("Upper Screw", upperScrewLimit.get());
110
    	SmartDashboard.putBoolean("Lower Pinion", lowerPinionLimit.get());
111
    	SmartDashboard.putBoolean("Upper Pinion", upperPinionLimit.get());
112
    }
113
    public Boolean goToMiddle() {
114
    	/// make sure pinion is at bottom
115
	    	if (!lowerPinionLimit.get()) {
116
    			leftPinion.set(ControlMode.PercentOutput, leftPinionate(-1));
117
    			rightPinion.set(ControlMode.PercentOutput, rightPinionate(-1));
118
    		}
119
    		else {
120
    			leftPinion.set(ControlMode.PercentOutput, 0);
121
    			rightPinion.set(ControlMode.PercentOutput, 0);
122
    		}
123
    	/// move screw to middle
124
	    	if (midScrewLimit.get()) {
125
	    		screw.set(ControlMode.PercentOutput, 0);
126
	    		return true;
127
	    	}
128
	    	else {
129
		    	switch (carriagePosition) {
130
			    	case UP:
131
			    		screw.set(ControlMode.PercentOutput, screwify(-1));
132
			    		break;
133
			    	case DOWN:
134
			    		screw.set(ControlMode.PercentOutput, screwify(1));
135
			    		break;
136
		    	}
137
		    	return false;
138
	    	}
139
	    }
140
    
141
    /** configures the voltage of each CANTalon */
142
    private void voltage(TalonSRX talon) {
0 ignored issues
show
Unused Code introduced by
Your method has more parameters than it evaluates. Consider removing talon.
Loading history...
143
    	// talon.configNominalOutputVoltage(0f, 0f);
144
    	// talon.configPeakOutputVoltage(12.0f, -12.0f);
145
    	// talon.enableCurrentLimit(true);
146
    	// talon.configContinuousCurrentLimit(35, 300);
147
    		// configContinuousCurrentLimit spat mean errors
148
    		// commented out for now, but we need to address it
149
    }
150
    
151
    
152
153
}
154
155