-
Notifications
You must be signed in to change notification settings - Fork 2
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
continued working on telescoping arm (ioreal/constants)
created sim file worked a lot on ioreal fixed depricated table command in io file removed pseudocode from main file made constants file with all variables temporarily set to 0
- Loading branch information
1 parent
12949c5
commit 2d160fc
Showing
5 changed files
with
185 additions
and
97 deletions.
There are no files selected for viewing
11 changes: 11 additions & 0 deletions
11
src/main/kotlin/com/team4099/robot2023/config/constants/TelescopingArmConstants.kt
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,16 @@ | ||
package com.team4099.robot2023.config.constants | ||
|
||
import org.team4099.lib.units.base.Length | ||
import org.team4099.lib.units.base.inches | ||
import org.team4099.lib.units.derived.volts | ||
|
||
object TelescopingArmConstants { | ||
val L_ARM_ID = 0 | ||
val R_ARM_ID = 0 | ||
|
||
val SENSOR_CPR = 0.0 | ||
val ARM_GEAR_RATIO = 0.0.inches | ||
val LEFT_SPOOL_RADIUS = 0.volts | ||
|
||
|
||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
167 changes: 151 additions & 16 deletions
167
src/main/kotlin/com/team4099/robot2023/subsystems/TelescopingArm/TelescopingArmIOReal.kt
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,20 +1,155 @@ | ||
package com.team4099.robot2023.subsystems.TelescopingArm | ||
|
||
import board.ctre.phoenix.motorcontrol.ControlMode | ||
import board.ctre.phoenix.motorcontrol.DemandType | ||
import board.ctre.phoenix.motorcontrol.NeutralMode | ||
import board.ctre.phoenix.motorcontrol.can.TalonFX | ||
import board.ctre.phoenix.motorcontrol.can.TalonFXConfiguration | ||
import board.team4099.lib.units.base.Length | ||
import board.team4099.lib.units.base.amps | ||
import board.team4099.lib.units.ctreLinearMechanismSensor | ||
import board.team4099.lib.units.derived.ElectricalPotential | ||
import board.team4099.lib.units.derived.inVolts | ||
import board.team4099.lib.units.derived.volts | ||
import board.team4099.robot2022.config.constants.Constants | ||
import board.team4099.robot2022.config.constants.Constants.Universal.CANIVORE_NAME | ||
import board.team4099.robot2022.config.constants.TelescopingClimberConstants | ||
package com.team4099.robot2022.subsystems.climber | ||
|
||
import com.ctre.phoenix6.configs.TalonFXConfiguration | ||
import com.revrobotics.CANSparkMax | ||
import com.revrobotics.CANSparkMaxLowLevel | ||
import org.team4099.lib.units.base.amps | ||
import org.team4099.lib.units.derived.ElectricalPotential | ||
import org.team4099.lib.units.derived.inVolts | ||
import org.team4099.lib.units.derived.volts | ||
import com.team4099.robot2023.config.constants.TelescopingArmConstants | ||
import com.team4099.robot2023.subsystems.TelescopingArm.TelescopingArmIO | ||
import org.team4099.lib.units.base.Length | ||
import org.team4099.lib.units.sparkMaxLinearMechanismSensor | ||
|
||
object TelescopingArmIOReal : TelescopingArmIO { | ||
private val telescopingLeftArm: CANSparkMax = CANSparkMax( | ||
TelescopingArmConstants.L_ARM_ID, | ||
CANSparkMaxLowLevel.MotorType.kBrushless | ||
) | ||
|
||
private val telescopingRightArm: CANSparkMax = CANSparkMax( | ||
TelescopingArmConstants.R_ARM_ID, | ||
CANSparkMaxLowLevel.MotorType.kBrushless | ||
) | ||
|
||
val telescopingLeftArmSensor = | ||
sparkMaxLinearMechanismSensor( | ||
telescopingLeftArm, | ||
TelescopingArmConstants.SENSOR_CPR, | ||
TelescopingArmConstants.ARM_GEAR_RATIO, | ||
TelescopingArmConstants.LEFT_SPOOL_RADIUS * 2 | ||
) | ||
|
||
val telescopingRightArmSensor = | ||
sparkMaxLinearMechanismSensor( | ||
telescopingRightArm, | ||
TelescopingArmConstants.SENSOR_CPR, | ||
TelescopingArmConstants.GEAR_RATIO, | ||
TelescopingArmConstants.RIGHT_SPOOL_RADIUS * 2 | ||
) | ||
|
||
private val telescopingConfiguration: TalonFXConfiguration = TalonFXConfiguration() | ||
|
||
val currentPosition: Length | ||
get() { | ||
return if (telescopingLeftArmSensor.position > telescopingRightArmSensor.position) { | ||
telescopingLeftArmSensor.position | ||
} else { | ||
telescopingRightArmSensor.position | ||
} | ||
} | ||
|
||
init { | ||
telescopingConfiguration.slot0.kP = TelescopingArmConstants.KP | ||
telescopingConfiguration.slot0.kI = TelescopingArmConstants.KI | ||
telescopingConfiguration.slot0.kD = TelescopingArmConstants.KD | ||
telescopingConfiguration.slot0.kF = TelescopingArmConstants.KFF | ||
|
||
telescopingRightArm.configFactoryDefault() | ||
telescopingRightArm.clearStickyFaults() | ||
telescopingRightArm.configAllSettings(telescopingConfiguration) | ||
telescopingRightArm.setNeutralMode(NeutralMode.Brake) | ||
telescopingRightArm.enableVoltageCompensation(0.0) //CHANGE CHANGE CHANGE CHANGE CHANGE CHANGE CHANGE | ||
telescopingRightArm.inverted = true | ||
telescopingRightArm.configForwardSoftLimitThreshold( | ||
telescopingRightArmSensor.positionToRawUnits( | ||
TelescopingArmConstants.FORWARD_SOFT_LIMIT | ||
) | ||
) | ||
telescopingRightArm.configForwardSoftLimitEnable(false) | ||
telescopingRightArm.configReverseSoftLimitThreshold( | ||
telescopingRightArmSensor.positionToRawUnits( | ||
TelescopingArmConstants.REVERSE_SOFT_LIMIT | ||
) | ||
) | ||
|
||
telescopingLeftArm.configFactoryDefault() | ||
telescopingLeftArm.clearStickyFaults() | ||
telescopingLeftArm.configAllSettings(telescopingConfiguration) | ||
telescopingLeftArm.setNeutralMode(NeutralMode.Brake) | ||
telescopingLeftArm.enableVoltageCompensation(0.0) //CHANGE CHANGE CHANGE CHANGE CHANGE CHANGE CHANGE | ||
telescopingLeftArm.inverted = false | ||
telescopingLeftArm.configForwardSoftLimitThreshold( | ||
telescopingLeftArmSensor.positionToRawUnits(TelescopingArmConstants.FORWARD_SOFT_LIMIT) | ||
) | ||
telescopingLeftArm.configForwardSoftLimitEnable(false) | ||
telescopingLeftArm.configReverseSoftLimitThreshold( | ||
telescopingLeftArmSensor.positionToRawUnits(TelescopingArmConstants.REVERSE_SOFT_LIMIT) | ||
) | ||
} | ||
|
||
override fun updateInputs(inputs: TelescopingArmIO.TelescopingArmIOInputs) { | ||
inputs.leftPosition = telescopingLeftArmSensor.position | ||
inputs.rightPosition = telescopingRightArmSensor.position | ||
|
||
inputs.leftVelocity = telescopingLeftArmSensor.velocity | ||
inputs.rightVelocity = telescopingRightArmSensor.velocity | ||
|
||
inputs.leftStatorCurrent = telescopingLeftArm.statorCurrent.amps | ||
inputs.rightStatorCurrent = telescopingRightArm.statorCurrent.amps | ||
|
||
inputs.leftSupplyCurrent = telescopingLeftArm.supplyCurrent.amps | ||
inputs.rightSupplyCurrent = telescopingRightArm.supplyCurrent.amps | ||
|
||
inputs.leftOutputVoltage = telescopingLeftArm.motorOutputVoltage.volts | ||
inputs.rightOutputVoltage = telescopingRightArm.motorOutputVoltage.volts | ||
|
||
inputs.leftTemperatureCelcius = telescopingLeftArm.temperature | ||
inputs.rightTemperatureCelcius = telescopingRightArm.temperature | ||
} | ||
|
||
override fun zeroLeftEncoder() { | ||
telescopingLeftArm.selectedSensorPosition = 0.0 | ||
} | ||
|
||
override fun zeroRightEncoder() { | ||
telescopingRightArm.selectedSensorPosition = 0.0 | ||
} | ||
|
||
override fun setLeftOpenLoop(percentOutput: Double) { | ||
telescopingLeftArm.set(ControlMode.PercentOutput, percentOutput) | ||
} | ||
|
||
override fun setRightOpenLoop(percentOutput: Double) { | ||
telescopingRightArm.set(ControlMode.PercentOutput, percentOutput) | ||
} | ||
|
||
override fun setLeftPosition(height: Length, feedforward: ElectricalPotential) { | ||
telescopingLeftArm.set( | ||
ControlMode.Position, | ||
telescopingLeftArmSensor.positionToRawUnits(height), | ||
DemandType.ArbitraryFeedForward, | ||
feedforward.inVolts / 12.0 | ||
) | ||
} | ||
|
||
override fun setRightPosition(height: Length, feedforward: ElectricalPotential) { | ||
telescopingRightArm.set( | ||
ControlMode.Position, | ||
telescopingRightArmSensor.positionToRawUnits(height), | ||
DemandType.ArbitraryFeedForward, | ||
feedforward.inVolts / 12.0 | ||
) | ||
} | ||
|
||
override fun configPID(kP: Double, kI: Double, kD: Double) { | ||
telescopingLeftArm.config_kP(0, kP) | ||
telescopingLeftArm.config_kI(0, kI) | ||
telescopingLeftArm.config_kD(0, kD) | ||
|
||
telescopingRightArm.config_kP(0, kP) | ||
telescopingRightArm.config_kI(0, kI) | ||
telescopingRightArm.config_kD(0, kD) | ||
} | ||
} |
4 changes: 4 additions & 0 deletions
4
src/main/kotlin/com/team4099/robot2023/subsystems/TelescopingArm/TelescopingArmIOSim.kt
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,4 @@ | ||
package com.team4099.robot2023.subsystems.TelescopingArm | ||
|
||
object TelescopingArmIOSim { | ||
} |