Skip to content
This repository has been archived by the owner on Dec 24, 2018. It is now read-only.

Commit

Permalink
Cleanup
Browse files Browse the repository at this point in the history
Signed-off-by: Alex Saveau <[email protected]>
  • Loading branch information
SUPERCILEX committed Jan 30, 2018
1 parent 7a2b808 commit eca2ef7
Show file tree
Hide file tree
Showing 7 changed files with 29 additions and 49 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
buildscript {
ext.kotlinVersion = '1.2.21'
ext.gradleRioVersion = '2018.01.22'
ext.sertainVersion = '0.0.2'
ext.sertainVersion = '0.0.3'
ext.ktlintVersion = '0.15.0'

repositories {
Expand Down
17 changes: 4 additions & 13 deletions src/main/java/org/sert2521/powerup/drivetrain/Drivetrain.kt
Original file line number Diff line number Diff line change
Expand Up @@ -9,38 +9,29 @@ import org.sert2521.powerup.util.LEFT_FRONT_MOTOR
import org.sert2521.powerup.util.LEFT_REAR_MOTOR
import org.sert2521.powerup.util.RIGHT_FRONT_MOTOR
import org.sert2521.powerup.util.RIGHT_REAR_MOTOR
import org.sertain.RobotLifecycle
import org.sertain.command.Subsystem
import org.sertain.hardware.Talon
import org.sertain.hardware.autoBreak
import org.sertain.hardware.plus
import org.sertain.hardware.resetEncoder

object Drivetrain : Subsystem(), RobotLifecycle {
object Drivetrain : Subsystem() {
val ahrs = AHRS(I2C.Port.kMXP)

val leftSpeed get() = leftDrive.get()
val rightSpeed get() = leftDrive.get()

private val leftDrive =
Talon(LEFT_FRONT_MOTOR).autoBreak() + Talon(LEFT_REAR_MOTOR).autoBreak()
private val rightDrive =
Talon(RIGHT_FRONT_MOTOR).autoBreak() + Talon(RIGHT_REAR_MOTOR).autoBreak()

private val drive = DifferentialDrive(leftDrive, rightDrive)

override val defaultCommand = TeleopDrive()

val leftSpeed get() = leftDrive.get()
val rightSpeed get() = leftDrive.get()

init {
leftDrive.autoBreak()
rightDrive.autoBreak()
}

override fun onStart() {
EmergencyAbort().start()

stop()

leftDrive.resetEncoder()
rightDrive.resetEncoder()
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,8 @@ class EmergencyAbort : Command() {
val avg = history.average()
if (avg.absoluteValue >= 16) {
println("EMERGENCY ABORT! ${avg.absoluteValue}")
FixedDrive(
leftSpeed - 0.01 * -avg.sign,
rightSpeed - 0.01 * -avg.sign
).start()
// Reduce speed until we aren't dying
FixedDrive(leftSpeed - 0.01 * -avg.sign, rightSpeed - 0.01 * -avg.sign).start()
}

return false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,8 @@ class TeleopDrive : Command() {

override fun execute(): Boolean {
when (controlMode) {
Control.Arcade -> Drivetrain.arcade(rightJoystick.x,
rightJoystick.y)
Control.Tank -> Drivetrain.tank(leftJoystick.y,
rightJoystick.y)
Control.Arcade -> Drivetrain.arcade(rightJoystick.x, rightJoystick.y)
Control.Tank -> Drivetrain.tank(leftJoystick.y, rightJoystick.y)
Control.Controller -> Drivetrain.arcade(
-controller.getY(GenericHID.Hand.kLeft),
controller.getX(GenericHID.Hand.kRight)
Expand Down
8 changes: 2 additions & 6 deletions src/main/java/org/sert2521/powerup/intake/Intake.kt
Original file line number Diff line number Diff line change
Expand Up @@ -3,21 +3,17 @@ package org.sert2521.powerup.intake
import org.sert2521.powerup.intake.commands.TeleopIntake
import org.sert2521.powerup.util.LEFT_INTAKE_MOTOR
import org.sert2521.powerup.util.RIGHT_INTAKE_MOTOR
import org.sertain.RobotLifecycle
import org.sertain.command.Subsystem
import org.sertain.hardware.Talon
import org.sertain.hardware.autoBreak
import org.sertain.hardware.inverted
import org.sertain.hardware.plus

object Intake : Subsystem(), RobotLifecycle {
object Intake : Subsystem() {
private val intake =
Talon(LEFT_INTAKE_MOTOR).inverted().autoBreak() + Talon(RIGHT_INTAKE_MOTOR).inverted().autoBreak()
Talon(LEFT_INTAKE_MOTOR).autoBreak() + Talon(RIGHT_INTAKE_MOTOR).autoBreak()

override val defaultCommand = TeleopIntake()

override fun onStart() = stop()

fun set(speed: Double) = intake.set(speed)

fun stop() = intake.stopMotor()
Expand Down
28 changes: 13 additions & 15 deletions src/main/java/org/sert2521/powerup/intake/commands/TeleopIntake.kt
Original file line number Diff line number Diff line change
Expand Up @@ -17,21 +17,19 @@ class TeleopIntake : Command() {
}

override fun execute(): Boolean {
if (controlMode == Control.Arcade || controlMode == Control.Tank) {
val speed = (rightJoystick.throttle - 1) / 2
var multiplier = 0

if (rightJoystick.getRawButton(1)) multiplier = 1
else if (rightJoystick.getRawButton(2)) multiplier = -1

Intake.set(speed * multiplier)
} else if (controlMode == Control.Controller) {
val leftSpeed = controller.getTriggerAxis(GenericHID.Hand.kLeft)
val rightSpeed = controller.getTriggerAxis(GenericHID.Hand.kRight)

val speed = leftSpeed - rightSpeed

Intake.set(speed)
when (controlMode) {
Control.Arcade, Control.Tank -> Intake.set(when {
rightJoystick.trigger -> 0.5
rightJoystick.top -> -0.5
else -> 0.0
})
Control.Controller -> {
val leftSpeed = controller.getTriggerAxis(GenericHID.Hand.kLeft)
val rightSpeed = controller.getTriggerAxis(GenericHID.Hand.kRight)

// Support variable intake speeds though self-cancellation
Intake.set(leftSpeed - rightSpeed)
}
}

return false
Expand Down
11 changes: 5 additions & 6 deletions src/main/java/org/sert2521/powerup/util/Oi.kt
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,14 @@ package org.sert2521.powerup.util
import edu.wpi.first.wpilibj.Joystick
import edu.wpi.first.wpilibj.XboxController

val leftJoystick: Joystick = Joystick(LEFT_STICK_PORT)
val rightJoystick: Joystick = Joystick(RIGHT_STICK_PORT)
val leftJoystick = Joystick(LEFT_STICK_PORT)
val rightJoystick = Joystick(RIGHT_STICK_PORT)
val secondaryJoystick = Joystick(SECONDARY_STICK_PORT)

val secondaryJoystick: Joystick = Joystick(SECONDARY_STICK_PORT)
val controller = XboxController(CONTROLLER_PORT)

val controller: XboxController = XboxController(CONTROLLER_PORT)
var controlMode = Control.Controller

enum class Control {
Arcade, Tank, Controller
}

var controlMode = Control.Controller

0 comments on commit eca2ef7

Please sign in to comment.