Skip to content

Commit

Permalink
updated constants
Browse files Browse the repository at this point in the history
  • Loading branch information
theKnightedBird committed May 14, 2024
1 parent b3aa249 commit 047acd4
Show file tree
Hide file tree
Showing 4 changed files with 170 additions and 115 deletions.
Original file line number Diff line number Diff line change
@@ -1,49 +1,36 @@
package frc.team449.robot2024.constants.subsystem

import com.ctre.phoenix6.signals.InvertedValue
import com.ctre.phoenix6.signals.NeutralModeValue
import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap
import edu.wpi.first.math.util.Units
import kotlin.math.PI
import kotlin.math.pow

object SpinShooterConstants {
val BRAKE_MODE = false
const val EFFICIENCY = 0.8

const val DUTY_CYCLE_DEADBAND = 0.001
const val RIGHT_MOTOR_ID = 45
const val RIGHT_MOTOR_INVERTED = false
val RIGHT_MOTOR_ORIENTATION = InvertedValue.CounterClockwise_Positive
val RIGHT_NEUTRAL_MODE = NeutralModeValue.Coast
const val LEFT_MOTOR_ID = 46
const val LEFT_MOTOR_INVERTED = true
val LEFT_MOTOR_ORIENTATION = InvertedValue.CounterClockwise_Positive
val LEFT_NEUTRAL_MODE = NeutralModeValue.Coast

const val UPDATE_FREQUENCY = 100.0

const val STATOR_CURRENT_LIMIT = 150.0
const val SUPPLY_CURRENT_LIMIT = 40.0
const val BURST_CURRENT_LIMIT = 60.0
const val BURST_TIME_LIMIT = 0.25
const val CURRENT_LIMIT = 85
const val SECONDARY_CURRENT_LIMIT = 200.0

val SUBWOOFER_LEFT_SPEED = 3450.0 / 60
val SUBWOOFER_RIGHT_SPEED = 2800.0 / 60
val ANYWHERE_LEFT_SPEED = 4850.0 / 60
val ANYWHERE_RIGHT_SPEED = 3850.0 / 60
val PASS_LEFT_SPEED = 3900.0 / 60
val PASS_RIGHT_SPEED = 2900.0 / 60
val PASS2_LEFT_SPEED = 3550.0 / 60
val PASS2_RIGHT_SPEED = 2550.0 / 60
val PASS3_LEFT_SPEED = 3550.0 / 60
val PASS3_RIGHT_SPEED = 2550.0 / 60
val AMP_SPEED = 1800.0 / 60
val OUTTAKE_SPEED = -200.0 / 60
const val BRAKE_MODE = false

val SUBWOOFER_LEFT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(3450.0)
val SUBWOOFER_RIGHT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(2800.0)
val ANYWHERE_LEFT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(4850.0)
val ANYWHERE_RIGHT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(3850.0)
val PASS_LEFT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(3900.0)
val PASS_RIGHT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(2900.0)
val PASS2_LEFT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(3550.0)
val PASS2_RIGHT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(2550.0)
val PASS3_LEFT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(3550.0)
val PASS3_RIGHT_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(2550.0)
val AMP_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(1800.0)
val OUTTAKE_SPEED = Units.rotationsPerMinuteToRadiansPerSecond(-200.0)

const val AUTO_SHOOT_TOL = 25.0

val BRAKE_RATE_LIMIT = 5250.0 / 60
val BRAKE_RATE_LIMIT = Units.rotationsPerMinuteToRadiansPerSecond(5250.0)

val SHOOTING_MAP = InterpolatingDoubleTreeMap()
val TIME_MAP = InterpolatingDoubleTreeMap()
Expand All @@ -54,12 +41,6 @@ object SpinShooterConstants {
const val RIGHT_KV = 0.011597 // 0.010836
const val LEFT_KA = 0.0050 // 0.0061217
const val RIGHT_KA = 0.0060 // 0.00815
const val LEFT_KP = 0.2377 // 0.19599
const val RIGHT_KP = 0.32957 // 0.28982
const val LEFT_KI = 0.010607 // 0.010993
const val RIGHT_KI = 0.011597 // 0.010836
const val LEFT_KD = 0.0050 // 0.0061217
const val RIGHT_KD = 0.0060 // 0.00815

const val IN_TOLERANCE = 10.0
const val AIM_TOLERANCE = 15.0
Expand All @@ -83,7 +64,7 @@ object SpinShooterConstants {
const val INTERNAL_MEASUREMENT_PD = 24
const val ENCODER_DELAY = 0.00875
const val UPR = 2 * PI
const val GEARING = 1.0 / 2.0
const val GEARING = 2.0 / 1.0

val equation = { x: Double -> -78.7 + 2.18 * x - 0.0176 * x.pow(2) + 6.82e-5 * x.pow(3) - 1e-7 * x.pow(4) }

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
package frc.team449.robot2024.constants.subsystem

import com.ctre.phoenix6.signals.InvertedValue
import com.ctre.phoenix6.signals.NeutralModeValue
import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap
import edu.wpi.first.math.util.Units
import kotlin.math.pow

object SpinShooterKrakenConstants {

const val DUTY_CYCLE_DEADBAND = 0.001
const val RIGHT_MOTOR_ID = 45
val RIGHT_MOTOR_ORIENTATION = InvertedValue.CounterClockwise_Positive
val RIGHT_NEUTRAL_MODE = NeutralModeValue.Coast
const val LEFT_MOTOR_ID = 46
val LEFT_MOTOR_ORIENTATION = InvertedValue.CounterClockwise_Positive
val LEFT_NEUTRAL_MODE = NeutralModeValue.Coast

const val UPDATE_FREQUENCY = 100.0

const val STATOR_CURRENT_LIMIT = 150.0
const val SUPPLY_CURRENT_LIMIT = 40.0
const val BURST_CURRENT_LIMIT = 60.0
const val BURST_TIME_LIMIT = 0.25

val SUBWOOFER_LEFT_SPEED = 3450.0 / 60
val SUBWOOFER_RIGHT_SPEED = 2800.0 / 60
val ANYWHERE_LEFT_SPEED = 4850.0 / 60
val ANYWHERE_RIGHT_SPEED = 3850.0 / 60
val PASS_LEFT_SPEED = 3900.0 / 60
val PASS_RIGHT_SPEED = 2900.0 / 60
val PASS2_LEFT_SPEED = 3550.0 / 60
val PASS2_RIGHT_SPEED = 2550.0 / 60
val PASS3_LEFT_SPEED = 3550.0 / 60
val PASS3_RIGHT_SPEED = 2550.0 / 60
val AMP_SPEED = 1800.0 / 60
val OUTTAKE_SPEED = -200.0 / 60

const val AUTO_SHOOT_TOL = 25.0

val BRAKE_RATE_LIMIT = 5250.0 / 60

val SHOOTING_MAP = InterpolatingDoubleTreeMap()
val TIME_MAP = InterpolatingDoubleTreeMap()

const val LEFT_KS = 0.2377 // 0.19599
const val RIGHT_KS = 0.32957 // 0.28982
const val LEFT_KV = 0.010607 // 0.010993
const val RIGHT_KV = 0.011597 // 0.010836
const val LEFT_KA = 0.0050 // 0.0061217
const val RIGHT_KA = 0.0060 // 0.00815
const val LEFT_KP = 1.0
const val RIGHT_KP = 1.0
const val LEFT_KI = 0.0
const val RIGHT_KI = 0.0
const val LEFT_KD = 0.0
const val RIGHT_KD = 0.0

val IN_TOLERANCE = Units.radiansPerSecondToRotationsPerMinute(10.0) / 60
val AIM_TOLERANCE = Units.radiansPerSecondToRotationsPerMinute(15.0) / 60
val AMP_TOLERANCE = Units.radiansPerSecondToRotationsPerMinute(75.0) / 60
val MIN_COAST_VEL = Units.radiansPerSecondToRotationsPerMinute(15.0) / 60

const val GEARING = 1.0 / 2.0

val equation = { x: Double -> -78.7 + 2.18 * x - 0.0176 * x.pow(2) + 6.82e-5 * x.pow(3) - 1e-7 * x.pow(4) }

init {
/**
* Data is entered as follows:
* SHOOTING_MAP.put(distanceToSpeaker, pivotAngle)
*/
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -672,7 +672,7 @@ open class SpinShooter(
depth = SpinShooterConstants.INTERNAL_ENC_DEPTH
),
inverted = SpinShooterConstants.RIGHT_MOTOR_INVERTED,
currentLimit = SpinShooterConstants.STATOR_CURRENT_LIMIT.toInt(),
currentLimit = SpinShooterConstants.CURRENT_LIMIT,
secondaryCurrentLimit = SpinShooterConstants.SECONDARY_CURRENT_LIMIT,
enableBrakeMode = SpinShooterConstants.BRAKE_MODE
)
Expand All @@ -687,7 +687,7 @@ open class SpinShooter(
depth = SpinShooterConstants.INTERNAL_ENC_DEPTH
),
inverted = SpinShooterConstants.LEFT_MOTOR_INVERTED,
currentLimit = SpinShooterConstants.STATOR_CURRENT_LIMIT.toInt(),
currentLimit = SpinShooterConstants.CURRENT_LIMIT,
secondaryCurrentLimit = SpinShooterConstants.SECONDARY_CURRENT_LIMIT,
enableBrakeMode = SpinShooterConstants.BRAKE_MODE
)
Expand Down
Loading

0 comments on commit 047acd4

Please sign in to comment.