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

Commit

Permalink
Merge remote-tracking branch 'origin/main' into log-inputs
Browse files Browse the repository at this point in the history
  • Loading branch information
doinkythederp committed Jan 24, 2024
2 parents b4381ad + 1b86662 commit 9e8714e
Show file tree
Hide file tree
Showing 4 changed files with 38 additions and 18 deletions.
12 changes: 6 additions & 6 deletions src/main/java/com/frcteam3636/frc2024/CAN.kt
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@ enum class REVMotorControllerId(val num: Int) {
BackLeftTurningMotor(2),
BackRightTurningMotor(3),
FrontRightTurningMotor(4),
LeftShooterFlywheel(0),
RightShooterFlywheel(0),
OverTheBumperIntakeArm(0),
OverTheBumperIntakeFeed(0),
UnderTheBumperIntakeRoller(0),
ClimberMotor(0),
LeftShooterFlywheel(15),
RightShooterFlywheel(7),
OverTheBumperIntakeArm(31),
OverTheBumperIntakeFeed(32),
UnderTheBumperIntakeRoller(33),
ClimberMotor(34),

}

Expand Down
9 changes: 4 additions & 5 deletions src/main/java/com/frcteam3636/frc2024/RobotContainer.kt
Original file line number Diff line number Diff line change
@@ -1,14 +1,13 @@
package com.frcteam3636.frc2024

import com.frcteam3636.frc2024.subsystems.intake.Intake
import com.frcteam3636.frc2024.subsystems.drivetrain.Drivetrain
import com.frcteam3636.frc2024.subsystems.intake.Intake
import com.frcteam3636.frc2024.subsystems.shooter.Shooter
import edu.wpi.first.wpilibj.Joystick
import edu.wpi.first.wpilibj2.command.Command
import edu.wpi.first.wpilibj2.command.button.CommandXboxController




/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
* "declarative" paradigm, very little robot logic should actually be handled in the [Robot]
Expand All @@ -27,14 +26,14 @@ object RobotContainer {

init {
configureBindings()
// Shooter
Shooter.register()
Drivetrain.register()
Intake.register()
}

/** Use this method to define your `trigger->command` mappings. */
private fun configureBindings() {
// controller.b().whileTrue(Shooter.shootCommand())
controller.x().whileTrue(Shooter.shootCommand())
controller.b().whileTrue(Intake.intakeCommand())
Drivetrain.defaultCommand =
Drivetrain.driveWithJoysticks(translationJoystick = joystickLeft, rotationJoystick = joystickRight)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,24 @@ package com.frcteam3636.frc2024.subsystems.shooter

import org.littletonrobotics.junction.LogTable
import org.littletonrobotics.junction.inputs.LoggableInputs
import edu.wpi.first.math.geometry.Rotation2d
import org.littletonrobotics.junction.LogTable
import org.littletonrobotics.junction.inputs.LoggableInputs


interface ShooterIO {
class ShooterIOInputs: LoggableInputs {
override fun fromLog(table: LogTable?) {
var leftSpeed = Rotation2d()
var rightSpeed = Rotation2d()

override fun toLog(table: LogTable) {
table.put("Left Speed", leftSpeed)
table.put("Right Speed", rightSpeed)
}

override fun toLog(table: LogTable?) {

override fun fromLog(table: LogTable) {
leftSpeed = table.get("Left Speed", leftSpeed)[0]
rightSpeed = table.get("Right Speed", rightSpeed)[0]
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,24 +3,37 @@ package com.frcteam3636.frc2024.subsystems.shooter
import com.frcteam3636.frc2024.can.CANSparkMax
import com.frcteam3636.frc2024.can.REVMotorControllerId
import com.revrobotics.CANSparkLowLevel
import edu.wpi.first.math.geometry.Rotation2d
import edu.wpi.first.math.util.Units


class ShooterIOReal : ShooterIO {

private val left = CANSparkMax(REVMotorControllerId.LeftShooterFlywheel, CANSparkLowLevel.MotorType.kBrushless)
private val right = CANSparkMax(REVMotorControllerId.RightShooterFlywheel, CANSparkLowLevel.MotorType.kBrushless)
companion object {
const val FLYWHEEL_GEAR_RATIO = 1.0
}

private val left = CANSparkMax(REVMotorControllerId.LeftShooterFlywheel, CANSparkLowLevel.MotorType.kBrushless).apply {
inverted = true
encoder.velocityConversionFactor = Units.rotationsToRadians(1.0) * FLYWHEEL_GEAR_RATIO / 60
}

private val right = CANSparkMax(REVMotorControllerId.RightShooterFlywheel, CANSparkLowLevel.MotorType.kBrushless).apply {
encoder.velocityConversionFactor = Units.rotationsToRadians(1.0) * FLYWHEEL_GEAR_RATIO / 60
}

init {
left.inverted = true
}

override fun updateInputs(inputs: ShooterIO.ShooterIOInputs?) {
// no-op
inputs?.leftSpeed = Rotation2d(left.encoder.velocity)
inputs?.rightSpeed = Rotation2d(right.encoder.velocity)
}

override fun shoot(speed: Double) {
left.set(speed)
right.set(speed * 0.5)
right.set(speed)
}

override fun intake(speed: Double) {
Expand Down

0 comments on commit 9e8714e

Please sign in to comment.