Skip to content

Commit 579b745

Browse files
committed
Merge branch 'main' into intake
2 parents c176856 + 1a6d57c commit 579b745

File tree

6 files changed

+192
-0
lines changed

6 files changed

+192
-0
lines changed

.github/workflows/gradle.yml

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,36 @@
1+
# This workflow uses actions that are not certified by GitHub.
2+
# They are provided by a third-party and are governed by
3+
# separate terms of service, privacy policy, and support
4+
# documentation.
5+
# This workflow will build a Java project with Gradle and cache/restore any dependencies to improve the workflow execution time
6+
# For more information see: https://docs.github.com/en/actions/automating-builds-and-tests/building-and-testing-java-with-gradle
7+
8+
name: Java CI with Gradle
9+
10+
on:
11+
push:
12+
branches: [ "main" ]
13+
pull_request:
14+
branches: [ "main" ]
15+
16+
permissions:
17+
contents: read
18+
19+
jobs:
20+
build:
21+
22+
runs-on: ubuntu-latest
23+
24+
steps:
25+
- uses: actions/checkout@v3
26+
- name: Set up JDK 17
27+
uses: actions/setup-java@v3
28+
with:
29+
java-version: '17'
30+
distribution: 'temurin'
31+
- name: Grant execute permission for gradlew
32+
run: chmod +x gradlew
33+
- name: Build with Gradle
34+
uses: gradle/gradle-build-action@67421db6bd0bf253fb4bd25b31ebb98943c375e1
35+
with:
36+
arguments: build

.github/workflows/linter.yml

Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
---
2+
#################################
3+
#################################
4+
## Super Linter GitHub Actions ##
5+
#################################
6+
#################################
7+
name: Lint Code Base
8+
9+
#
10+
# Documentation:
11+
# https://docs.github.com/en/actions/learn-github-actions/workflow-syntax-for-github-actions
12+
#
13+
14+
#############################
15+
# Start the job on all push #
16+
#############################
17+
on:
18+
push:
19+
branches-ignore: [master, main]
20+
# Remove the line above to run when pushing to master
21+
pull_request:
22+
branches: [master, main]
23+
24+
###############
25+
# Set the Job #
26+
###############
27+
jobs:
28+
build:
29+
# Name the Job
30+
name: Lint Code Base
31+
# Set the agent to run on
32+
runs-on: ubuntu-latest
33+
34+
##################
35+
# Load all steps #
36+
##################
37+
steps:
38+
##########################
39+
# Checkout the code base #
40+
##########################
41+
- name: Checkout Code
42+
uses: actions/checkout@v3
43+
with:
44+
# Full git history is needed to get a proper
45+
# list of changed files within `super-linter`
46+
fetch-depth: 0
47+
################################
48+
# Run Linter against code base #
49+
################################
50+
- name: Lint Code Base
51+
uses: github/super-linter/slim@v4
52+
env:
53+
VALIDATE_ALL_CODEBASE: false
54+
VALIDATE_EDITORCONFIG: true
55+
# Change to 'master' if your main branch differs
56+
DEFAULT_BRANCH: main
57+
GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
58+

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

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,10 +8,14 @@
88
import edu.wpi.first.wpilibj2.command.Command;
99
import edu.wpi.first.wpilibj2.command.Commands;
1010
import frc.robot.subsystems.Intake.Intake;
11+
import frc.robot.subsystems.Transporter.Transporter;
12+
1113

1214

1315
public class RobotContainer {
1416
public static final Intake INTAKE = new Intake();
17+
public static final Transporter TRANSPORTER = new Transporter();
18+
1519

1620
public RobotContainer() {
1721
configureBindings();
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)