Skip to content

Commit 1a6d57c

Browse files
authored
Transporter (#3)
* added Transporter package and Transporter subsystem * added TransporterConstants and TransporterCommands * Update Transporter.java * added code to transporterConstants * created getSetMotorOutputCommand(not finished).) * changed talonsrx to wpi talonsrx * added 3 states at which the transporter can be in collect eject and rest * enabled Voltage compensation * Update TransporterConstants.java * Update TransporterCommands.java * Update TransporterConstants.java * Update TransporterCommands.java * changed enum to use proper voltage percentage * changed getSetMotorOutputCommand from a functional command to a startend command * Update Transporter.java
1 parent c223a04 commit 1a6d57c

File tree

4 files changed

+105
-11
lines changed

4 files changed

+105
-11
lines changed

src/main/java/frc/robot/RobotContainer.java

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -7,22 +7,22 @@
77

88
import edu.wpi.first.wpilibj2.command.Command;
99
import edu.wpi.first.wpilibj2.command.Commands;
10+
import frc.robot.subsystems.Transporter.Transporter;
1011

1112

13+
public class RobotContainer {
14+
public static final Transporter TRANSPORTER = new Transporter();
1215

13-
public class RobotContainer
14-
{
15-
public RobotContainer()
16-
{
16+
public RobotContainer() {
1717
configureBindings();
1818
}
19-
20-
21-
private void configureBindings() {}
22-
23-
24-
public Command getAutonomousCommand()
25-
{
19+
20+
21+
private void configureBindings() {
22+
}
23+
24+
25+
public Command getAutonomousCommand() {
2626
return Commands.print("No autonomous command configured");
2727
}
2828
}
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
package frc.robot.subsystems.Transporter;
2+
3+
import com.ctre.phoenix.motorcontrol.ControlMode;
4+
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
5+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
6+
7+
public class Transporter extends SubsystemBase {
8+
private final TalonSRX rightMotor = TransporterConstants.RIGHT_MOTOR;
9+
private final TalonSRX leftMotor = TransporterConstants.LEFT_MOTOR;
10+
11+
void stopMotors() {
12+
setTargetPercentageVoltageOutput(0);
13+
}
14+
15+
void setTargetPercentageVoltageOutput(double percentageMotorOutput) {
16+
rightMotor.set(ControlMode.PercentOutput, percentageMotorOutput);
17+
leftMotor.set(ControlMode.PercentOutput, percentageMotorOutput);
18+
}
19+
}
20+
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
package frc.robot.subsystems.Transporter;
2+
3+
import edu.wpi.first.wpilibj2.command.Command;
4+
import edu.wpi.first.wpilibj2.command.StartEndCommand;
5+
import frc.robot.RobotContainer;
6+
7+
public class TransporterCommands {
8+
public static Command getSetTargetStateCommand(TransporterConstants.TransporterState targetState) {
9+
return getSetMotorOutputCommand(targetState.targetMotorOutput);
10+
}
11+
12+
private static Command getSetMotorOutputCommand(double motorOutput) {
13+
return new StartEndCommand(
14+
() -> RobotContainer.TRANSPORTER.setTargetPercentageVoltageOutput(motorOutput),
15+
RobotContainer.TRANSPORTER::stopMotors,
16+
RobotContainer.TRANSPORTER
17+
);
18+
}
19+
}
Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
package frc.robot.subsystems.Transporter;
2+
3+
import com.ctre.phoenix.motorcontrol.InvertType;
4+
import com.ctre.phoenix.motorcontrol.NeutralMode;
5+
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
6+
7+
public class TransporterConstants {
8+
private static final int
9+
RIGHT_MOTOR_ID = 1,
10+
LEFT_MOTOR_ID = 2;
11+
12+
static final WPI_TalonSRX
13+
RIGHT_MOTOR = new WPI_TalonSRX(RIGHT_MOTOR_ID),
14+
LEFT_MOTOR = new WPI_TalonSRX(LEFT_MOTOR_ID);
15+
16+
private static final InvertType RIGHT_MOTOR_INVERTED_VALUE = InvertType.None;
17+
private static final InvertType LEFT_MOTOR_INVERTED_VALUE = InvertType.InvertMotorOutput;
18+
private static final NeutralMode NEUTRAL_MODE = NeutralMode.Coast;
19+
private static final double VOLTAGE_COMPENSATION_VALUE = 12;
20+
21+
static {
22+
configureRightMotor();
23+
configureLeftMotor();
24+
}
25+
26+
private static final void configureRightMotor() {
27+
RIGHT_MOTOR.configFactoryDefault();
28+
29+
RIGHT_MOTOR.setInverted(RIGHT_MOTOR_INVERTED_VALUE);
30+
RIGHT_MOTOR.setNeutralMode(NEUTRAL_MODE);
31+
RIGHT_MOTOR.enableVoltageCompensation(true);
32+
RIGHT_MOTOR.configVoltageCompSaturation(VOLTAGE_COMPENSATION_VALUE);
33+
}
34+
35+
private static final void configureLeftMotor() {
36+
LEFT_MOTOR.configFactoryDefault();
37+
38+
LEFT_MOTOR.setInverted(LEFT_MOTOR_INVERTED_VALUE);
39+
LEFT_MOTOR.setNeutralMode(NEUTRAL_MODE);
40+
LEFT_MOTOR.enableVoltageCompensation(true);
41+
LEFT_MOTOR.configVoltageCompSaturation(VOLTAGE_COMPENSATION_VALUE);
42+
}
43+
44+
public enum TransporterState {
45+
COLLECT(0.5),
46+
EJECT(-0.5),
47+
REST(0);
48+
49+
final double targetMotorOutput;
50+
51+
TransporterState(double setTransporterState) {
52+
this.targetMotorOutput = setTransporterState;
53+
}
54+
}
55+
}

0 commit comments

Comments
 (0)