Skip to content

Commit

Permalink
clean build robot
Browse files Browse the repository at this point in the history
  • Loading branch information
ShriyanReyya27 committed Jan 30, 2024
1 parent 645a815 commit b6f70e2
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,4 +19,4 @@ object ClimberConstants {

const val MAX_SIM_POS = 1.5
const val SIM_SPEED = 0.25
}
}
43 changes: 20 additions & 23 deletions src/main/kotlin/frc/team449/robot2024/subsystems/Climber.kt
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,8 @@ import frc.team449.robot2024.constants.subsystem.ClimberConstants
import frc.team449.system.encoder.NEOEncoder
import frc.team449.system.motor.WrappedMotor
import frc.team449.system.motor.createSparkMax
import kotlin.math.abs
import kotlin.math.sign


class Climber(
private val robot: Robot,
private val rightMotor: WrappedMotor,
Expand All @@ -24,26 +22,26 @@ class Climber(
) : SubsystemBase() {
private var simCurrentPos = 0.0

fun levelClimb() : Command {
return PIDCommand(
controller,
{ robot.drive.roll.degrees },
{ 0.0 },
{ value ->
rightMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT + value)
leftMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT - value)
},
this
)
}

fun extend(): Command {
return this.runOnce {
rightMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE)
leftMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE)
}
fun levelClimb(): Command {
return PIDCommand(
controller,
{ robot.drive.roll.degrees },
{ 0.0 },
{ value ->
rightMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT + value)
leftMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT - value)
},
this
)
}

fun extend(): Command {
return this.runOnce {
rightMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE)
leftMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE)
}
}

fun retract(): Command {
return this.runOnce {
rightMotor.setVoltage(ClimberConstants.RETRACT_VOLTAGE)
Expand All @@ -63,7 +61,8 @@ class Climber(
builder.addDoubleProperty("1.1 Last Right Voltage", { rightMotor.lastVoltage }, null)
builder.addDoubleProperty("1.2 Last Left Voltage", { leftMotor.lastVoltage }, null)
builder.publishConstString("2.0", "Advantage Scope 3D Pos")
builder.addDoubleArrayProperty("2.1 3D Position",
builder.addDoubleArrayProperty(
"2.1 3D Position",
{
doubleArrayOf(
0.0,
Expand All @@ -82,7 +81,6 @@ class Climber(
super.simulationPeriodic()

simCurrentPos += MathUtil.clamp(ClimberConstants.SIM_SPEED * RobotConstants.LOOP_TIME * sign(leftMotor.lastVoltage), 0.0, ClimberConstants.MAX_SIM_POS)

}

companion object {
Expand All @@ -109,7 +107,6 @@ class Climber(
currentLimit = ClimberConstants.CURRENT_LIM,
)


val controller = PIDController(ClimberConstants.KP, ClimberConstants.KI, ClimberConstants.KD)

return Climber(robot, rightMotor, leftMotor, controller)
Expand Down

0 comments on commit b6f70e2

Please sign in to comment.