Skip to content

Commit db22000

Browse files
conclude merge
2 parents c601646 + 1f159ea commit db22000

File tree

8 files changed

+132
-11
lines changed

8 files changed

+132
-11
lines changed

.github/workflows/main.yml

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
name: Gradle Build
2+
3+
on:
4+
push:
5+
branches: [ master ]
6+
pull_request:
7+
branches: [ master ]
8+
9+
jobs:
10+
build:
11+
runs-on: ubuntu-latest
12+
steps:
13+
- uses: actions/checkout@v2
14+
- name: Set up JDK 11
15+
uses: actions/setup-java@v2
16+
with:
17+
java-version: '11'
18+
distribution: 'adopt'
19+
- name: Gradle Build
20+
run: ./gradlew build

.wpilib/wpilib_preferences.json

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
{
22
"enableCppIntellisense": false,
33
"currentLanguage": "java",
4-
"projectYear": "2020",
4+
"projectYear": "2021",
55
"teamNumber": 2036
6-
}
6+
}

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
plugins {
22
id "java"
3-
id "edu.wpi.first.GradleRIO" version "2020.3.2"
3+
id "edu.wpi.first.GradleRIO" version "2021.3.1"
44
id "org.jetbrains.kotlin.jvm" version "1.3.50"
55
}
66

src/main/kotlin/frc/robot/RobotContainer.kt

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,7 @@ class RobotContainer {
7777
/*** --- commands --- ***/
7878
//drive by a joystick (controller1)
7979
val XboxDriveCommand = XboxDrive(drivetrain, controller1)
80+
val XboxDriveSpecial = XboxDrive(drivetrain, controller1)
8081

8182
/** -- 0 point autos -- **/
8283
val noAuto = DriveDoubleSupplier(drivetrain, { 0.0 }, { 0.0 })
@@ -225,13 +226,17 @@ class RobotContainer {
225226

226227
/* setup default commands */
227228
drivetrain.defaultCommand = XboxDriveCommand
229+
//drivetrain.defaultCommand = XboxDriveSpecial
230+
228231
/* default gate - run forward on X, backwards on A
229232
* If left bumper held, run until a ball is seen by the sensor
230233
*/
231234
gate.defaultCommand = SensoredFixedGateSpeed(gate, {
232235
if (controller0.xButton) Constants.kGateSpeed else (
233236
if (controller0.aButton) -Constants.kGateSpeed else (
234-
if (controller0.getBumper(kLeft)) Constants.kGateLoadSpeed else 0.0
237+
if (controller0.getBumper(kLeft)) Constants.kGateLoadSpeed else (
238+
if (controller0.getTriggerAxis(kLeft) >= Constants.kTriggerThresh) -Constants.kGateLoadSpeed else 0.0
239+
)
235240
))
236241
}, {
237242
/* only run in sensored mode if controller0 left bumper held */
@@ -298,13 +303,6 @@ class RobotContainer {
298303
}
299304

300305
fun getAutonomousCommand(): Command {
301-
if (gate.isBallTriggered()) {
302-
return pathPlanningCommand("paths/", drivetrain) // update
303-
} else{
304-
return pathPlanningCommand("paths/", drivetrain)
305-
}
306-
307-
308306
// Return the selected command
309307
return m_autoCommandChooser.selected
310308
}

src/main/kotlin/frc/robot/commands/CompositeShoot.kt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ class CompositeShoot(val intakeSubsystem: IntakeSubsystem, val indexerSubsystem:
4141
/* run shooter full speed */
4242
/* wait for a time to run gate to allow */
4343
if (timer.get() > Constants.kShooterSpinUpTime) {
44+
shooterSubsystem.setSpeed(Constants.kShooterSpeed)
4445
/* pulse gate to slow down balls going into shooter */
4546
if (timer.get() % Constants.kGatePulseTime < Constants.kGatePulseTime / 2) {
4647
gateSubsystem.setSpeed(Constants.kGateSpeed)
Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
/*----------------------------------------------------------------------------*/
2+
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
3+
/* Open Source Software - may be modified and shared by FRC teams. The code */
4+
/* must be accompanied by the FIRST BSD license file in the root directory of */
5+
/* the project. */
6+
/*----------------------------------------------------------------------------*/
7+
8+
package frc.robot.commands
9+
10+
import edu.wpi.first.wpilibj.GenericHID
11+
import edu.wpi.first.wpilibj.XboxController
12+
import edu.wpi.first.wpilibj2.command.CommandBase
13+
import frc.robot.subsystems.DrivetrainSubsystem
14+
import kotlin.math.abs
15+
import kotlin.math.pow
16+
17+
/**
18+
* Drive the drivetrain based on a joystick
19+
*/
20+
class XboxDriveSpecial(val driveSubsystem: DrivetrainSubsystem, val controller: XboxController) : CommandBase() {
21+
init {
22+
addRequirements(driveSubsystem)
23+
}
24+
25+
fun joystickToSpeed(joystickPosSigned: Double): Double {
26+
val gainSwitchThresh = 0.25
27+
val gainSwitchPos = 0.25
28+
29+
val modPower = 4
30+
val joystickPos = abs(joystickPosSigned)
31+
val joystickSign = (joystickPosSigned / joystickPos)
32+
return if (joystickPos < gainSwitchThresh) {
33+
joystickPosSigned * (gainSwitchPos / gainSwitchThresh)
34+
} else {
35+
((joystickPos - gainSwitchThresh).pow(modPower) * joystickSign * 1.1) + (gainSwitchPos * joystickSign)
36+
}
37+
}
38+
39+
fun joystickToRadius(joystickPosSigned: Double) : Double {
40+
val gainSwitchThresh = 0.25
41+
val gainSwitchPos = 0.25
42+
43+
val radiusMod = 2 // make this a constant after tuning is finished!
44+
val radiusPower = 2 // see above
45+
46+
val joystickPos = abs(joystickPosSigned)
47+
val joystickPosSign = (joystickPosSigned / joystickPos)
48+
return if (joystickPos < gainSwitchThresh) {
49+
joystickPosSigned * (gainSwitchPos / gainSwitchThresh) // probably bad but eh
50+
} else {
51+
radiusMod * joystickPosSign * (1/(joystickPos - gainSwitchThresh).pow(radiusPower) - 1 + (gainSwitchPos * joystickPosSign))
52+
}
53+
}
54+
55+
56+
override fun execute() {
57+
driveSubsystem.driveArcadeSpecial(-controller.getY(GenericHID.Hand.kLeft), joystickToRadius(controller.getX(GenericHID.Hand.kRight)), false)
58+
}
59+
60+
override fun end(interrupted: Boolean) {
61+
driveSubsystem.driveArcadeSpecial(0.0, 0.0, true)
62+
}
63+
64+
override fun isFinished() = false
65+
}
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
package frc.robot.subsystems
2+
3+
import edu.wpi.first.wpilibj2.command.CommandBase
4+
import frc.robot.subsystems.DrivetrainSubsystem
5+
6+
7+
class DriveDoubleSpecialSupplier(val driveSubsystem: DrivetrainSubsystem, val forwardSpeed: () -> Double, val turnRadius: () -> Double) : CommandBase() {
8+
init {
9+
addRequirements(driveSubsystem)
10+
}
11+
12+
override fun execute() {
13+
driveSubsystem.driveArcade(forwardSpeed(), turnRadius())
14+
}
15+
16+
override fun end(interrupted: Boolean) {
17+
driveSubsystem.driveArcadeSpecial(0.0, 0.0, true)
18+
}
19+
20+
override fun isFinished() = false
21+
22+
}

src/main/kotlin/frc/robot/subsystems/DrivetrainSubsystem.kt

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase
1212
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard
1313
import frc.robot.Constants
1414
import kotlin.math.IEEErem
15+
import kotlin.math.abs
16+
import kotlin.math.min
1517

1618
/**
1719
* Drivetrain subsystem
@@ -99,4 +101,17 @@ class DrivetrainSubsystem(val leftSpeedController: SpeedControllerGroup, val rig
99101
setMaxOutput(1.0)
100102
drivetrain.arcadeDrive(forwardSpeed, turnSpeed, squareInputs)
101103
}
104+
105+
/* drive with a stick setting turn radius rather than speed*/
106+
fun driveArcadeSpecial(forwardSpeed: Double, turnRadius: Double, squareInputs: Boolean = false){
107+
setMaxOutput(1.0)
108+
var xSpeed = turnRadius + (0.5*Constants.kTrackwidthMeters)
109+
var ySpeed = turnRadius - (0.5*Constants.kTrackwidthMeters)
110+
111+
var normMin = min(xSpeed, ySpeed)
112+
xSpeed = xSpeed/abs(normMin)
113+
ySpeed = ySpeed/abs(normMin)
114+
115+
drivetrain.tankDrive(xSpeed, ySpeed, squareInputs)
116+
}
102117
}

0 commit comments

Comments
 (0)