001package com.ctre.phoenix.motorcontrol.can; 002import com.ctre.phoenix.motorcontrol.MotorCommutation; 003 004import com.ctre.phoenix.motorcontrol.StatorCurrentLimitConfiguration; 005import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration; 006import com.ctre.phoenix.motorcontrol.FeedbackDevice; 007import com.ctre.phoenix.sensors.AbsoluteSensorRange; 008import com.ctre.phoenix.sensors.SensorInitializationStrategy; 009 010/** 011 * Configurables available to TalonFX 012 */ 013public class TalonFXConfiguration extends com.ctre.phoenix.motorcontrol.can.BaseTalonConfiguration { 014 015 /** 016 * Supply-side current limiting. This is typically used to prevent breakers from tripping. 017 */ 018 public SupplyCurrentLimitConfiguration supplyCurrLimit = new SupplyCurrentLimitConfiguration(); 019 /** 020 * Stator-side current limiting. This is typically used to limit acceleration/torque and heat generation. 021 */ 022 public StatorCurrentLimitConfiguration statorCurrLimit = new StatorCurrentLimitConfiguration(); 023 024 /** 025 * Choose the type of motor commutation. 026 */ 027 public MotorCommutation motorCommutation = MotorCommutation.Trapezoidal; 028 029 /** 030 * Desired Sign / Range for the absolute position register. 031 * Choose unsigned for an absolute range of[0, +1) rotations, [0, 360) deg, etc. 032 * Choose signed for an absolute range of[-0.5, +0.5) rotations, [-180, +180) deg, etc. 033 */ 034 public AbsoluteSensorRange absoluteSensorRange = AbsoluteSensorRange.Unsigned_0_to_360; 035 /** 036 * Adjusts the zero point for the absolute position register. 037 * The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) 038 * and a hard-limited mechanism may have such a discontinuity in its functional range. 039 * In which case use this config to move the discontinuity outside of the function range. 040 */ 041 public double integratedSensorOffsetDegrees = 0; 042 /** 043 * The sensor initialization strategy to use.This will impact the behavior the next time device boots up. 044 * 045 * Pick the strategy on how to initialize the "Position" register. Depending on the mechanism, 046 * it may be desirable to auto set the Position register to match the Absolute Position(swerve for example). 047 * Or it may be desired to zero the sensor on boot(drivetrain translation sensor or a relative servo). 048 * 049 * TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the device is reset. 050 */ 051 public SensorInitializationStrategy initializationStrategy = SensorInitializationStrategy.BootToZero; 052 053 public TalonFXConfiguration() { 054 super(FeedbackDevice.IntegratedSensor); 055 } 056 057 /** 058 * @return String representation of all the configs 059 */ 060 public String toString() { 061 return toString(""); 062 } 063 064 /** 065 * @param prependString 066 * String to prepend to all the configs 067 * @return String representation of all the configs 068 */ 069 public String toString(String prependString) { 070 String retstr = prependString + ".supplyCurrLimit = " + supplyCurrLimit.toString() + ";\n"; 071 retstr += prependString + ".statorCurrLimit = " + statorCurrLimit.toString() + ";\n"; 072 retstr += prependString + ".motorCommutation = " + motorCommutation.toString() + ";\n"; 073 retstr += prependString + ".absoluteSensorRange = " + absoluteSensorRange.toString() + ";\n"; 074 retstr += prependString + ".integratedSensorOffsetDegrees = " + integratedSensorOffsetDegrees + ";\n"; 075 retstr += prependString + ".initializationStrategy = " + initializationStrategy.toString() + ";\n"; 076 retstr += super.toString(prependString); 077 078 return retstr; 079 } 080 081} 082