Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

motor current and temperature alerts #34

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ import edu.wpi.first.wpilibj.RobotBase
import org.team4099.lib.units.Velocity
import org.team4099.lib.units.base.Meter
import org.team4099.lib.units.base.amps
import org.team4099.lib.units.base.celsius
import org.team4099.lib.units.base.feet
import org.team4099.lib.units.base.grams
import org.team4099.lib.units.base.inMeters
Expand Down Expand Up @@ -77,6 +78,9 @@ object DrivetrainConstants {
val DRIVE_STATOR_THRESHOLD_CURRENT_LIMIT = 80.0.amps
val DRIVE_STATOR_TRIGGER_THRESHOLD_TIME = 1.0.seconds

val STEERING_TEMP_ALERT = 80.celsius
val DRIVE_TEMP_ALERT = 80.celsius

val FRONT_LEFT_MODULE_ZERO = 1.33.radians
val FRONT_RIGHT_MODULE_ZERO = 4.51.radians
val BACK_LEFT_MODULE_ZERO = 3.20.radians
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ import com.team4099.robot2023.config.constants.FieldConstants.Grids.midCubeZ
import com.team4099.robot2023.config.constants.FieldConstants.LoadingZone.doubleSubstationShelfZ
import org.team4099.lib.units.base.Length
import org.team4099.lib.units.base.amps
import org.team4099.lib.units.base.celsius
import org.team4099.lib.units.base.inches
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.base.percent
Expand Down Expand Up @@ -59,6 +60,8 @@ object ElevatorConstants {
val VOLTAGE_COMPENSATION = 12.volts
val PHASE_CURRENT_LIMIT = 80.amps // TODO tune stator current limit

val ELEVATOR_TEMP_ALERT = 80.celsius

// TODO figure out what these should be
val HOMING_POSITION_THRESHOLD = 30.inches
val HOMING_APPLIED_VOLTAGE = -1.volts
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package com.team4099.robot2023.config.constants

import org.team4099.lib.units.base.amps
import org.team4099.lib.units.base.celsius
import org.team4099.lib.units.base.grams
import org.team4099.lib.units.base.inches
import org.team4099.lib.units.base.meters
Expand Down Expand Up @@ -40,6 +41,9 @@ object GroundIntakeConstants {
val ROLLER_CURRENT_LIMIT = 30.amps // TODO TUNE
val ARM_CURRENT_LIMIT = 50.amps // TODO TUNE

val ROLLER_TEMP_ALERT = 80.celsius
val ARM_TEMP_ALERT = 80.celsius

const val ROLLER_MOTOR_INVERTED = true
const val ARM_MOTOR_INVERTED = false

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ package com.team4099.robot2023.config.constants

import org.team4099.lib.units.base.Length
import org.team4099.lib.units.base.amps
import org.team4099.lib.units.base.celsius
import org.team4099.lib.units.base.grams
import org.team4099.lib.units.base.inches
import org.team4099.lib.units.base.meters
Expand Down Expand Up @@ -52,6 +53,9 @@ object ManipulatorConstants {
val ARM_STATOR_CURRENT_LIMIT = 20.amps
val ROLLER_STATOR_CURRENT_LIMIT = 40.amps

val ROLLER_TEMP_ALERT = 80.celsius
val ARM_TEMP_ALERT = 80.celsius

val ARM_VOLTAGE_COMPENSATION = 12.volts
val ROLLER_VOLTAGE_COMPENSATION = 12.volts

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ import com.ctre.phoenix.motorcontrol.can.TalonFX
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration
import com.team4099.robot2023.config.constants.Constants
import com.team4099.robot2023.config.constants.DrivetrainConstants
import com.team4099.robot2023.util.Alert
import edu.wpi.first.wpilibj.AnalogInput
import edu.wpi.first.wpilibj.RobotController
import org.littletonrobotics.junction.Logger
Expand Down Expand Up @@ -70,6 +71,18 @@ class SwerveModuleIOFalcon(
}
}

private val steeringCurrentLimitAlert =
Alert("$label steering motor surpassed current limit", Alert.AlertType.ERROR)

private val driveCurrentLimitAlert =
Alert("$label drive motor surpassed current limit", Alert.AlertType.ERROR)

private val steeringTempAlert =
Alert("$label steering motor surpassed temperature limit", Alert.AlertType.ERROR)

private val driveTempAlert =
Alert("$label drive motor surpassed temperature limit", Alert.AlertType.ERROR)

init {
driveFalcon.configFactoryDefault()
steeringFalcon.configFactoryDefault()
Expand Down Expand Up @@ -163,6 +176,20 @@ class SwerveModuleIOFalcon(
Logger.getInstance()
.recordOutput("$label/sensorVelocityRawUnits", driveFalcon.selectedSensorVelocity)
Logger.getInstance().recordOutput("$label/motorOutput", driveFalcon.motorOutputPercent)

driveCurrentLimitAlert.set(
driveFalcon.statorCurrent.amps > DrivetrainConstants.DRIVE_STATOR_CURRENT_LIMIT
)

steeringCurrentLimitAlert.set(
steeringFalcon.statorCurrent.amps > DrivetrainConstants.DRIVE_STATOR_CURRENT_LIMIT
)

driveTempAlert.set(driveFalcon.temperature.celsius > DrivetrainConstants.DRIVE_TEMP_ALERT)

steeringTempAlert.set(
steeringFalcon.temperature.celsius > DrivetrainConstants.STEERING_TEMP_ALERT
)
}

override fun setSteeringSetpoint(angle: Angle) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@ import com.revrobotics.SparkMaxPIDController
import com.team4099.lib.math.clamp
import com.team4099.robot2023.config.constants.Constants
import com.team4099.robot2023.config.constants.ElevatorConstants
import com.team4099.robot2023.subsystems.motorchecker.MotorChecker
import com.team4099.robot2023.subsystems.motorchecker.Neo
import com.team4099.robot2023.util.Alert
import org.team4099.lib.units.base.Length
import org.team4099.lib.units.base.Meter
import org.team4099.lib.units.base.amps
Expand Down Expand Up @@ -40,6 +43,18 @@ object ElevatorIONeo : ElevatorIO {

private val leaderPIDController: SparkMaxPIDController = leaderSparkMax.pidController

private val leftCurrentLimitAlert =
Alert("Left Elevator motor surpassed current limit", Alert.AlertType.ERROR)

private val rightCurrentLimitAlert =
Alert("Right Elevator motor surpassed current limit", Alert.AlertType.ERROR)

private val leftTempAlert =
Alert("Left Elevator motor surpassed temperature limit", Alert.AlertType.ERROR)

private val rightTempAlert =
Alert("Right Elevator motor surpassed temperature limit", Alert.AlertType.ERROR)

init {

// reseting motor
Expand Down Expand Up @@ -71,6 +86,8 @@ object ElevatorIONeo : ElevatorIO {

leaderSparkMax.burnFlash()
followerSparkMax.burnFlash()

MotorChecker.add(Neo(leaderSparkMax))
}

override fun updateInputs(inputs: ElevatorIO.ElevatorInputs) {
Expand Down Expand Up @@ -100,6 +117,22 @@ object ElevatorIONeo : ElevatorIO {
inputs.followerSupplyCurrent = inputs.followerStatorCurrent * followerSparkMax.appliedOutput

inputs.followerTempCelcius = followerSparkMax.motorTemperature.celsius

leftCurrentLimitAlert.set(
followerSparkMax.outputCurrent.amps > ElevatorConstants.PHASE_CURRENT_LIMIT
)

rightCurrentLimitAlert.set(
leaderSparkMax.outputCurrent.amps > ElevatorConstants.PHASE_CURRENT_LIMIT
)

leftTempAlert.set(
followerSparkMax.motorTemperature.celsius > ElevatorConstants.ELEVATOR_TEMP_ALERT
)

rightTempAlert.set(
leaderSparkMax.motorTemperature.celsius > ElevatorConstants.ELEVATOR_TEMP_ALERT
)
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ import com.revrobotics.SparkMaxPIDController
import com.team4099.lib.math.clamp
import com.team4099.robot2023.config.constants.Constants
import com.team4099.robot2023.config.constants.GroundIntakeConstants
import com.team4099.robot2023.util.Alert
import edu.wpi.first.wpilibj.DutyCycleEncoder
import org.littletonrobotics.junction.Logger
import org.team4099.lib.units.base.amps
Expand Down Expand Up @@ -80,6 +81,18 @@ object GroundIntakeIONeo : GroundIntakeIO {
.degrees
}

private val rollerCurrentLimitAlert =
Alert("Ground intake roller motor surpassed current limit", Alert.AlertType.ERROR)

private val armCurrentLimitAlert =
Alert("Ground arm motor surpassed current limit", Alert.AlertType.ERROR)

private val rollerTempAlert =
Alert("Ground intake roller motor surpassed temperature limit", Alert.AlertType.ERROR)

private val armTempAlert =
Alert("Ground arm motor surpassed temperature limit", Alert.AlertType.ERROR)

init {
rollerSparkMax.restoreFactoryDefaults()
rollerSparkMax.clearFaults()
Expand Down Expand Up @@ -140,6 +153,20 @@ object GroundIntakeIONeo : GroundIntakeIO {
armSparkMax.encoder.velocity *
GroundIntakeConstants.ARM_OUTPUT_GEAR_RATIO.asDrivenOverDriving
)

rollerCurrentLimitAlert.set(
rollerSparkMax.outputCurrent.amps > GroundIntakeConstants.ROLLER_CURRENT_LIMIT
)

armCurrentLimitAlert.set(
armSparkMax.outputCurrent.amps > GroundIntakeConstants.ARM_CURRENT_LIMIT
)

rollerTempAlert.set(
rollerSparkMax.motorTemperature.celsius > GroundIntakeConstants.ROLLER_TEMP_ALERT
)

armTempAlert.set(armSparkMax.motorTemperature.celsius > GroundIntakeConstants.ARM_TEMP_ALERT)
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ import com.revrobotics.SparkMaxPIDController
import com.team4099.lib.math.clamp
import com.team4099.robot2023.config.constants.Constants
import com.team4099.robot2023.config.constants.ManipulatorConstants
import com.team4099.robot2023.util.Alert
import org.team4099.lib.units.base.Length
import org.team4099.lib.units.base.Meter
import org.team4099.lib.units.base.amps
Expand Down Expand Up @@ -42,6 +43,18 @@ object ManipulatorIONeo : ManipulatorIO {
)
private val armPIDController: SparkMaxPIDController = armSparkMax.pidController

private val rollerCurrentLimitAlert =
Alert("Manipulator roller motor surpassed current limit", Alert.AlertType.ERROR)

private val armCurrentLimitAlert =
Alert("Manipulator extension motor surpassed current limit", Alert.AlertType.ERROR)

private val rollerTempAlert =
Alert("Manipulator roller motor surpassed temperature limit", Alert.AlertType.ERROR)

private val armTempAlert =
Alert("Manipulator extension motor surpassed temperature limit", Alert.AlertType.ERROR)

init {
// resetting the motors
rollerSparkMax.restoreFactoryDefaults()
Expand Down Expand Up @@ -118,6 +131,20 @@ object ManipulatorIONeo : ManipulatorIO {
// percentOutput * statorCurrent
inputs.armSupplyCurrent = inputs.armStatorCurrent * armSparkMax.appliedOutput
inputs.armTemp = armSparkMax.motorTemperature.celsius

rollerCurrentLimitAlert.set(
rollerSparkMax.outputCurrent.amps > ManipulatorConstants.ROLLER_STATOR_CURRENT_LIMIT
)

armCurrentLimitAlert.set(
armSparkMax.outputCurrent.amps > ManipulatorConstants.ARM_STATOR_CURRENT_LIMIT
)

rollerTempAlert.set(
rollerSparkMax.motorTemperature.celsius > ManipulatorConstants.ROLLER_TEMP_ALERT
)

armTempAlert.set(armSparkMax.motorTemperature.celsius > ManipulatorConstants.ARM_TEMP_ALERT)
}

/**
Expand Down
Loading