Package tagalong.subsystems.micro.confs
Class MicrosystemConf
java.lang.Object
tagalong.subsystems.micro.confs.MicrosystemConf
- Direct Known Subclasses:
ElevatorConf
,PivotConf
,RollerConf
Configuration for a microsystem
-
Field Summary
FieldsModifier and TypeFieldDescriptionfinal double
Default lower tolerancefinal DistanceUnits
Unit of default tolerancesfinal double
Default upper tolerancefinal String[]
The can bus of the motorsfinal com.ctre.phoenix6.configs.TalonFXConfiguration[]
Motor configurationsfinal int[]
The can ids of the motorsfinal com.ctre.phoenix6.signals.InvertedValue[]
The motor directionalityfinal com.ctre.phoenix6.signals.NeutralModeValue[]
Motor brake mode while robot is disabledfinal com.ctre.phoenix6.signals.NeutralModeValue[]
Motor brake mode while robot is enabledfinal double
Net gear ratio of they system motor to mechanismfinal Motors[]
The type of each motor in the microsystemfinal String
Full microsystem name, default is subsystem name followed by microsystem namefinal int
Number of motors used by microsystem, also the length of the following arraysfinal AccelerationUnits
Unit of trapezoidal motion accelerationTrapezoidal constraintsfinal double
Trapezoidal motion acceleration limitsfinal double
Trapezoidal motion velocity limitsfinal VelocityUnits
Unit of trapezoidal motion velocity -
Constructor Summary
ConstructorsConstructorDescriptionMicrosystemConf
(String name, Motors[] motorTypes, int[] motorDeviceIDs, String[] motorCanBus, com.ctre.phoenix6.signals.InvertedValue[] motorDirection, com.ctre.phoenix6.signals.NeutralModeValue[] motorEnabledBrakeMode, com.ctre.phoenix6.signals.NeutralModeValue[] motorDisabledBrakeMode, int[][] gearRatio, DistanceUnits trapezoidalLengthUnit, VelocityUnits trapezoidalVelocityUnit, double trapezoidalLimitsVelocity, AccelerationUnits trapezoidalAccelerationUnit, double trapezoidalLimitsAcceleration, DistanceUnits defaultTolerancesUnit, double defaultLowerTolerance, double defaultUpperTolerance, com.ctre.phoenix6.configs.CurrentLimitsConfigs currentLimitsConfigs, PIDSGVAConstants slot0, PIDSGVAConstants slot1, PIDSGVAConstants slot2, PIDSGVAConstants simSlot0, PIDSGVAConstants simSlot1, PIDSGVAConstants simSlot2) -
Method Summary
-
Field Details
-
name
Full microsystem name, default is subsystem name followed by microsystem name -
numMotors
Number of motors used by microsystem, also the length of the following arrays -
motorTypes
The type of each motor in the microsystem -
motorDeviceIDs
The can ids of the motors -
motorCanBus
The can bus of the motors -
motorDirection
The motor directionality -
motorEnabledBrakeMode
Motor brake mode while robot is enabled -
motorDisabledBrakeMode
Motor brake mode while robot is disabled -
motorToMechRatio
Net gear ratio of they system motor to mechanism -
trapezoidalVelocityUnit
Unit of trapezoidal motion velocity -
trapezoidalAccelerationUnit
Unit of trapezoidal motion acceleration -
trapezoidalLimitsVelocity
Trapezoidal motion velocity limits -
trapezoidalLimitsAcceleration
Trapezoidal motion acceleration limits -
trapezoidalLimits
Trapezoidal constraints -
defaultTolerancesUnit
Unit of default tolerances -
defaultLowerTolerance
Default lower tolerance -
defaultUpperTolerance
Default upper tolerance -
motorConfig
Motor configurations
-
-
Constructor Details
-
MicrosystemConf
public MicrosystemConf(String name, Motors[] motorTypes, int[] motorDeviceIDs, String[] motorCanBus, com.ctre.phoenix6.signals.InvertedValue[] motorDirection, com.ctre.phoenix6.signals.NeutralModeValue[] motorEnabledBrakeMode, com.ctre.phoenix6.signals.NeutralModeValue[] motorDisabledBrakeMode, int[][] gearRatio, DistanceUnits trapezoidalLengthUnit, VelocityUnits trapezoidalVelocityUnit, double trapezoidalLimitsVelocity, AccelerationUnits trapezoidalAccelerationUnit, double trapezoidalLimitsAcceleration, DistanceUnits defaultTolerancesUnit, double defaultLowerTolerance, double defaultUpperTolerance, com.ctre.phoenix6.configs.CurrentLimitsConfigs currentLimitsConfigs, PIDSGVAConstants slot0, PIDSGVAConstants slot1, PIDSGVAConstants slot2, PIDSGVAConstants simSlot0, PIDSGVAConstants simSlot1, PIDSGVAConstants simSlot2) - Parameters:
name
- microsystem namemotorTypes
- motor typesmotorDeviceIDs
- motor device IDsmotorCanBus
- motor can busmotorDirection
- motor directionsmotorEnabledBrakeMode
- enabled brake mode for the motormotorDisabledBrakeMode
- disabled brake mode for the motorgearRatio
- gear ratiotrapezoidalLengthUnit
- unit for trapezoidal lengthtrapezoidalVelocityUnit
- unit for trapezoidal velocitytrapezoidalLimitsVelocity
- trapezoidal velocity limitstrapezoidalAccelerationUnit
- unit for trapezoidal accelerationtrapezoidalLimitsAcceleration
- trapezoidal acceleration limitsdefaultTolerancesUnit
- unit for default tolerancesdefaultLowerTolerance
- default lower tolerancedefaultUpperTolerance
- default upper tolerancecurrentLimitsConfigs
- configurations for current limitsslot0
- slot 0 configurationsslot1
- slot 1 configurationsslot2
- slot 2 configurationssimSlot0
- simulation slot 0 configurationssimSlot1
- simulation slot 1 configurationssimSlot2
- simulation slot 2 configurations
-
-
Method Details
-
calculateGearRatio
- Parameters:
gearPairs
- Pairs of gear teeth representing the physical path to the motor. e.g if the motor is using a 14-tooth pinion to a 60-tooth gear, the input should be [[14, 60]]- Returns:
- The resulting gear ratio coefficient. A reduction (target spinning slower than motor) results in a value g.t. 1 An up-duction (target spinning faster than motor) will result in a value l.t. 1
-