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

Commit

Permalink
Motor naming scheme changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Daniel1464 committed Jan 11, 2024
1 parent ee7f4b7 commit 56b68a0
Show file tree
Hide file tree
Showing 7 changed files with 209 additions and 177 deletions.
7 changes: 0 additions & 7 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -104,13 +104,6 @@ allprojects {
}
}

/*
task(checkAkitInstall, dependsOn: "classes", type: JavaExec) {
mainClass = "org.littletonrobotics.junction.CheckInstall"
classpath = sourceSets.main.runtimeClasspath
}
compileJava.finalizedBy checkAkitInstall
*/

wpi.java.configureExecutableTasks(jar)
wpi.java.configureTestTasks(test)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,12 @@ public final class ChargerLibBuildConstants {
public static final String MAVEN_GROUP = "frc.chargers";
public static final String MAVEN_NAME = "ChargerLib";
public static final String VERSION = "1.0.0";
public static final int GIT_REVISION = 264;
public static final String GIT_SHA = "8e4c95b743ed5868a6845f080b865f9124e386e9";
public static final String GIT_DATE = "2024-01-10T21:55:23Z";
public static final int GIT_REVISION = 265;
public static final String GIT_SHA = "ee7f4b7338449c562107ed35bd7ed41ee07a969d";
public static final String GIT_DATE = "2024-01-10T22:13:04Z";
public static final String GIT_BRANCH = "master";
public static final String BUILD_DATE = "2024-01-10T22:08:12Z";
public static final long BUILD_UNIX_TIME = 1704942492477L;
public static final String BUILD_DATE = "2024-01-10T22:57:40Z";
public static final long BUILD_UNIX_TIME = 1704945460325L;
public static final int DIRTY = 1;

private ChargerLibBuildConstants(){}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,40 +19,11 @@ import frc.chargers.hardware.configuration.safeConfigure
import frc.chargers.hardware.motorcontrol.*
import frc.chargers.hardware.sensors.encoders.ResettableEncoder
import frc.chargers.utils.math.inputModulus
import frc.chargers.wpilibextensions.delay
import com.ctre.phoenix6.configs.TalonFXConfiguration

/**
* Creates an instance of a falcon motor, controlled by a TalonFX motor controller.
*
* This function supports inline configuration using the "[configure]" lambda function,
* which has the context of a [ChargerTalonFXConfiguration].
*
* You do not need to manually factory default this motor, as it is factory defaulted on startup,
* before configuration. This setting can be changed by setting factoryDefault = false.
*
* ```
* // example
* val motor = falcon(canId = 6){ feedbackRemoteSensorId = 5 }
* An adaptor to the encoder of a [TalonFX].
*/
public fun falcon(
canId: Int,
canBus: String = "rio",
factoryDefault: Boolean = true,
configure: ChargerTalonFXConfiguration.() -> Unit = {}
): ChargerTalonFX = ChargerTalonFX(canId, canBus).apply {
// factory defaults configs on startup when factoryDefault = true
if (factoryDefault) {
configurator.apply(TalonFXConfiguration(), 0.02)
}
val config = ChargerTalonFXConfiguration().apply(configure)
if (config != ChargerTalonFXConfiguration()){
configure(config)
}
}



public class TalonFXEncoderAdapter(
private val motorController: TalonFX
): ResettableEncoder {
Expand All @@ -76,17 +47,65 @@ public class TalonFXEncoderAdapter(



/**
* Creates an instance of a [ChargerTalonFX] through a "[configure]" lambda function,
* which has the context of a [ChargerTalonFXConfiguration].
*
* ```
* // example
* val motor = ChargerTalonFX(canId = 6){ feedbackRemoteSensorId = 5 }
*/
public inline fun ChargerTalonFX(
deviceId: Int,
canBus: String = "rio",
factoryDefault: Boolean = true,
configure: ChargerTalonFXConfiguration.() -> Unit
): ChargerTalonFX = ChargerTalonFX(
deviceId, canBus, factoryDefault,
ChargerTalonFXConfiguration().apply(configure)
)




/**
* Represents a TalonFX motor controller.
* Includes everything in the CTRE TalonFX class,
* but has additional features to mesh better with the rest
* of this library.
*
* Creating an instance of this class factory will factory default the motor;
* set factoryDefault = false to turn this off.
*
* @see com.ctre.phoenix6.hardware.TalonFX
* @see ChargerTalonFXConfiguration
*/
public open class ChargerTalonFX(deviceNumber: Int, canBus: String = "rio"):
TalonFX(deviceNumber, canBus), SmartEncoderMotorController, HardwareConfigurable<ChargerTalonFXConfiguration> {
public open class ChargerTalonFX(
deviceId: Int,
canBus: String = "rio",
factoryDefault: Boolean = true,
configuration: ChargerTalonFXConfiguration? = null
): TalonFX(deviceId, canBus), SmartEncoderMotorController, HardwareConfigurable<ChargerTalonFXConfiguration> {

init{
val baseConfig = TalonFXConfiguration()
var baseConfigHasChanged = false

if (!factoryDefault){
configurator.refresh(baseConfig)
baseConfigHasChanged = true
}

if (configuration != null){
applyChanges(baseConfig, configuration)
baseConfigHasChanged = true
}

if (baseConfigHasChanged){
configurator.apply(baseConfig)
}
}


@Suppress("LeakingThis") // Known to be safe; CTREMotorControllerEncoderAdapter ONLY uses final functions
// and does not pass around the reference to this class.
Expand Down Expand Up @@ -265,7 +284,6 @@ public open class ChargerTalonFX(deviceNumber: Int, canBus: String = "rio"):
if (RobotBase.isSimulation()){
println("A Phoenix Device did not configure properly; however, this was ignored because the code is running in simulation.")
}else{
delay(200.milli.seconds)
allConfigErrors.add(this)
configAppliedProperly = false
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,22 +79,65 @@ public class TalonSRXEncoderAdapter(
}
}




/**
* Creates an instance of a [ChargerTalonSRX] through a "[configure]" lambda function,
* which has the context of a [ChargerTalonSRXConfiguration].
*
* ```
* // example
* val motor = ChargerTalonSRX(canId = 6){ feedbackRemoteSensorId = 5 }
*/
public inline fun ChargerTalonSRX(
deviceNumber: Int,
encoderTicksPerRotation: Int,
factoryDefault: Boolean = true,
configure: ChargerTalonSRXConfiguration.() -> Unit
): ChargerTalonSRX = ChargerTalonSRX(
deviceNumber, encoderTicksPerRotation, factoryDefault,
ChargerTalonSRXConfiguration().apply(configure)
)




/**
* Represents a TalonSRX motor controller.
* Includes everything in the CTRE TalonSRX class,
* but has additional features to mesh better with the rest
* of this library.
* Note: The ChargerTalonSRX still uses phoenix v5, as phoenix v6 scraps support for the TalonSRX.
*
*
* Creating an instance of this class factory will factory default the motor;
* set factoryDefault = false to turn this off.
*
* In addition, the ChargerTalonSRX still uses phoenix v5,
* as phoenix v6 scraps support for the TalonSRX.
*
* @see com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX
* @see ChargerTalonSRXConfiguration
*/
public open class ChargerTalonSRX(
public class ChargerTalonSRX(
deviceNumber: Int,
private val encoderTicksPerRotation: Int
private val encoderTicksPerRotation: Int,
factoryDefault: Boolean = true,
configuration: ChargerTalonSRXConfiguration? = null
) : WPI_TalonSRX(deviceNumber), EncoderMotorController, HardwareConfigurable<ChargerTalonSRXConfiguration>{

final override val encoder: Encoder
init{
if (factoryDefault){
configFactoryDefault()
}

if (configuration != null){
configure(configuration)
}
}


override val encoder: Encoder
get() = TalonSRXEncoderAdapter(
ctreMotorController = this,
pidIndex = 0,
Expand Down Expand Up @@ -140,7 +183,7 @@ public open class ChargerTalonSRX(
}


final override fun configure(configuration: ChargerTalonSRXConfiguration) {
override fun configure(configuration: ChargerTalonSRXConfiguration) {
configuration.inverted?.let(::setInverted)
configuration.expiration?.let { expiration = it.inUnit(seconds) }
configuration.safetyEnabled?.let(::setSafetyEnabled)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,35 +16,6 @@ import frc.chargers.hardware.motorcontrol.rev.util.*
import frc.chargers.utils.revertIfInvalid
import frc.chargers.wpilibextensions.delay

/**
* A convenience function to create a [ChargerSparkFlex].
*
* This function supports inline configuration using the "[configure]" lambda function,
* which has the context of a [ChargerSparkMaxConfiguration] object.
*
* You do not need to manually factory default this motor, as it is factory defaulted on startup,
* before configuration. This setting can be changed by setting factoryDefault = false.
*
* Example:
* ```
* val neo = neoSparkFlex(deviceId = 5){ inverted = false }
*/
public inline fun neoSparkFlex(
deviceId: Int,
factoryDefault: Boolean = true,
configure: ChargerSparkFlexConfiguration.() -> Unit = {}
): ChargerSparkFlex = ChargerSparkFlex(deviceId)
.apply {
if (factoryDefault) {
restoreFactoryDefaults()
delay(200.milli.seconds)
println("SparkFlex has been factory defaulted.")
}
val config = ChargerSparkFlexConfiguration().apply(configure)
configure(config)
}



/**
* Represents a type of spark flex encoder.
Expand Down Expand Up @@ -110,19 +81,62 @@ public class ChargerSparkFlexConfiguration(



/**
* A convenience function to create a [ChargerSparkFlex],
* which uses a function with the context of a [ChargerSparkFlexConfiguration]
* to configure the motor.
*
* Like the constructor, this function factory defaults the motor by default;
* set factoryDefault = false to turn this off.
*
* ```
* // example
* val neo = ChargerSparkFlex(5){ inverted = false }
*/
public inline fun ChargerSparkFlex(
deviceId: Int,
factoryDefault: Boolean = true,
configure: ChargerSparkFlexConfiguration.() -> Unit
): ChargerSparkFlex = ChargerSparkFlex(
deviceId, factoryDefault,
ChargerSparkFlexConfiguration().apply(configure)
)




/**
* A wrapper around REV's [CANSparkFlex], with support for Kmeasure units
* and integration with the rest of the library.
*
* Creating an instance of this class factory will factory default the motor;
* set factoryDefault = false to turn this off.
*
* @see ChargerSparkFlexConfiguration
* @see com.revrobotics.CANSparkFlex
*/
public class ChargerSparkFlex(deviceId: Int) :
CANSparkFlex(deviceId, MotorType.kBrushless), SmartEncoderMotorController, HardwareConfigurable<ChargerSparkFlexConfiguration> {
public class ChargerSparkFlex(
deviceId: Int,
factoryDefault: Boolean = true,
configuration: ChargerSparkFlexConfiguration? = null
) : CANSparkFlex(deviceId, MotorType.kBrushless), SmartEncoderMotorController, HardwareConfigurable<ChargerSparkFlexConfiguration> {

init{
if (factoryDefault) {
restoreFactoryDefaults()
delay(200.milli.seconds)
println("SparkMax has been factory defaulted.")
}
if (configuration != null){
configure(configuration)
}
}

private var encoderType: SparkFlexEncoderType = SparkFlexEncoderType.Regular()

override var encoder: SparkEncoderAdaptor = getEncoder(encoderType)
private set


private fun getEncoder(encoderType: SparkFlexEncoderType): SparkEncoderAdaptor{
this.encoderType = encoderType

Expand Down Expand Up @@ -192,7 +206,6 @@ public class ChargerSparkFlex(deviceId: Int) :
.also{ previousVoltage = it }



/**
* Adds a generic amount of followers to the Spark Max.
*
Expand Down
Loading

0 comments on commit 56b68a0

Please sign in to comment.