Test Failed
Pull Request — master (#114)
by
unknown
02:01
created

org.usfirst.frc.team3695.robot.subsystems.SubsystemMast   A

Complexity

Total Complexity 34

Size/Duplication

Total Lines 125
Duplicated Lines 0 %

Importance

Changes 0
Metric Value
wmc 34
dl 0
loc 125
c 0
b 0
f 0
rs 9.68

19 Methods

Rating   Name   Duplication   Size   Complexity  
screwify 0 3 ?
C moveBySpeed(Joystick,double) 0 14 9
setCarriagePosition 0 2 ?
A initDefaultCommand() 0 2 1
A publishSwitches() 0 6 1
goToMiddle 0 25 ?
rightPinionate 0 3 ?
leftPinionate 0 3 ?
B updateCarriage() 0 9 6
A screwify(double) 0 3 3
moveBySpeed 0 14 ?
A SubsystemMast() 0 12 1
A rightPinionate(double) 0 3 3
A voltage(TalonSRX) 0 1 1
updateCarriage 0 9 ?
publishSwitches 0 6 ?
A setCarriagePosition(Position) 0 2 1
A leftPinionate(double) 0 3 3
B goToMiddle() 0 25 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.Robot;
5
import org.usfirst.frc.team3695.robot.commands.ManualCommandDrive;
6
import org.usfirst.frc.team3695.robot.commands.ManualCommandGrow;
7
import org.usfirst.frc.team3695.robot.enumeration.Bot;
8
import org.usfirst.frc.team3695.robot.enumeration.Position;
9
import org.usfirst.frc.team3695.robot.util.Util;
10
import org.usfirst.frc.team3695.robot.util.Xbox;
11
12
import com.ctre.CANTalon;
13
import com.ctre.phoenix.motorcontrol.ControlMode;
14
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
15
16
import edu.wpi.first.wpilibj.DigitalInput;
17
import edu.wpi.first.wpilibj.Joystick;
18
import edu.wpi.first.wpilibj.command.Subsystem;
19
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
20
21
/** the big, metal pole */
22
public class SubsystemMast extends Subsystem {
23
	
24
	
25
	private TalonSRX leftPinion;
26
	private TalonSRX rightPinion;
27
	private TalonSRX screw;
28
	
29
	DigitalInput lowerPinionLimit;
30
    DigitalInput upperPinionLimit;
31
    DigitalInput lowerScrewLimit;
32
    DigitalInput midScrewLimit;
33
    DigitalInput upperScrewLimit;
34
    
35
    private Position carriagePosition;
36
    private Boolean midIsPressed;
0 ignored issues
show
Unused Code introduced by
Consider removing the unused private field midIsPressed.
Loading history...
37
38
	
39
	/** runs at robot boot */
40
    public void initDefaultCommand() {
41
    	setDefaultCommand(new ManualCommandGrow()); }
42
	
43
	/** gives birth to the CANTalons */
44
    public SubsystemMast(){
45
    	lowerPinionLimit = 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
        upperPinionLimit = 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...
47
        lowerScrewLimit  = new DigitalInput(1);
48
        upperScrewLimit  = 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...
49
    	
50
    	leftPinion = new TalonSRX(Constants.LEFT_PINION_MOTOR);
51
    	rightPinion = new TalonSRX(Constants.RIGHT_PINION_MOTOR);
52
    	screw = new TalonSRX(Constants.SCREW_MOTOR);
53
    		voltage(leftPinion);
54
    		voltage(rightPinion);
55
    		voltage(screw);
56
    }
57
58
   	
59
   	/** apply pinion motor invert */
60
   	public static final double leftPinionate(double left) {
61
   		Boolean invert = Robot.bot == Bot.OOF ? Constants.OOF.LEFT_PINION_MOTOR_INVERT : Constants.SWISS.LEFT_PINION_MOTOR_INVERT;
62
   		return left * (invert ? -1.0 : 1.0);
63
   	}
64
   	
65
   	/** apply screw motor invert */
66
   	public static final double rightPinionate(double right) {
67
   		Boolean invert = Robot.bot == Bot.OOF ? Constants.OOF.RIGHT_PINION_MOTOR_INVERT : Constants.SWISS.RIGHT_PINION_MOTOR_INVERT;
68
   		return right * (invert ? -1.0 : 1.0);
69
   	}
70
   	
71
   	public static final double screwify(double screw) {
72
   		Boolean invert = Robot.bot == Bot.OOF ? Constants.OOF.SCREW_MOTOR_INVERT : Constants.SWISS.SCREW_MOTOR_INVERT;
73
   		return screw * (invert ? -1.0 : 1.0);
74
   	}
75
    
76
   	/** raise the mast at RT-LR trigger speed */
77
    public void moveBySpeed(Joystick joy, double inhibitor) {
78
    	double screwSpeed = Xbox.RIGHT_Y(joy);
79
    	double pinionSpeed = Xbox.LEFT_Y(joy);
80
    	
81
		if (!lowerPinionLimit.get() && pinionSpeed > 1)   { pinionSpeed = 0; }
82
		if (!upperPinionLimit.get() && pinionSpeed < 0)   { pinionSpeed = 0; }
83
		if (!lowerScrewLimit.get()  && screwSpeed  > 1)   { screwSpeed = 0;  }
84
		if (!upperScrewLimit.get()  && screwSpeed  < 0)   { screwSpeed = 0;  }
85
			
86
		updateCarriage();
87
    	publishSwitches();
88
    	leftPinion.set(ControlMode.PercentOutput, leftPinionate(pinionSpeed));
89
    	rightPinion.set(ControlMode.PercentOutput, rightPinionate(pinionSpeed));
90
    	screw.set(ControlMode.PercentOutput, inhibitor * screwify(screwSpeed));
91
    }
92
    
93
    public void setCarriagePosition(Position position) {
94
    	carriagePosition = position;
95
    }
96
    
97
    public void updateCarriage() {
98
    	if (!midScrewLimit.get()) {
99
    		carriagePosition = Position.CENTER;
100
    	}
101
    	else if (carriagePosition == Position.CENTER && !midScrewLimit.get()) {
102
    		if (screw.getMotorOutputPercent() > 0) {
103
    			carriagePosition = Position.UP;
104
    		} else if (screw.getMotorOutputPercent() < 0) {
105
    			carriagePosition = Position.DOWN;
106
    		}
107
    	}
108
    }
109
    	
110
    public void publishSwitches() {
111
    	SmartDashboard.putBoolean("Lower Screw", !lowerScrewLimit.get());
112
    	SmartDashboard.putBoolean("Mid Position", !midScrewLimit.get());
113
    	SmartDashboard.putBoolean("Upper Screw", !upperScrewLimit.get());
114
    	SmartDashboard.putBoolean("Lower Pinion", !lowerPinionLimit.get());
115
    	SmartDashboard.putBoolean("Upper Pinion", !upperPinionLimit.get());
116
    }
117
    public Boolean goToMiddle() {
118
    	/// make sure pinion is at bottom
119
	    	if (!lowerPinionLimit.get()) {
120
    			leftPinion.set(ControlMode.PercentOutput, leftPinionate(-1));
121
    			rightPinion.set(ControlMode.PercentOutput, rightPinionate(-1));
122
    		}
123
    		else {
124
    			leftPinion.set(ControlMode.PercentOutput, 0);
125
    			rightPinion.set(ControlMode.PercentOutput, 0);
126
    		}
127
    	/// move screw to middle
128
	    	if (!midScrewLimit.get()) {
129
	    		screw.set(ControlMode.PercentOutput, 0);
130
	    		return true;
131
	    	}
132
	    	else {
133
		    	switch (carriagePosition) {
134
			    	case UP:
135
			    		screw.set(ControlMode.PercentOutput, screwify(-1));
136
			    		break;
137
			    	case DOWN:
138
			    		screw.set(ControlMode.PercentOutput, screwify(1));
139
			    		break;
140
		    	}
141
		    	return false;
142
	    	}
143
	    }
144
    
145
    /** configures the voltage of each CANTalon */
146
    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...
147
    	// talon.configNominalOutputVoltage(0f, 0f);
148
    	// talon.configPeakOutputVoltage(12.0f, -12.0f);
149
    	// talon.enableCurrentLimit(true);
150
    	// talon.configContinuousCurrentLimit(35, 300);
151
    		// configContinuousCurrentLimit spat mean errors
152
    		// commented out for now, but we need to address it
153
    }
154
    
155
    
156
157
}
158
159