001package tagalong.subsystems.micro.confs; 002 003import com.ctre.phoenix6.configs.CurrentLimitsConfigs; 004import com.ctre.phoenix6.signals.InvertedValue; 005import com.ctre.phoenix6.signals.NeutralModeValue; 006import tagalong.controls.FeedforwardConstants; 007import tagalong.controls.PIDSGVAConstants; 008import tagalong.devices.Motors; 009import tagalong.units.AccelerationUnits; 010import tagalong.units.DistanceUnits; 011import tagalong.units.VelocityUnits; 012 013/** 014 * Configuration for the flywheel 015 */ 016public class FlywheelConf extends RollerConf { 017 /** 018 * 019 * @param name name of the subsystem 020 * @param motorTypes array of motor types used 021 * @param motorDeviceIDs CAN IDs of the motors 022 * @param motorCanBus CAN buses which the motors are connected to 023 * @param motorDirection motor inversion settings 024 * @param motorEnabledBrakeMode brake mode when motors are enabled 025 * @param motorDisabledBrakeMode brake mode when motors are disabled 026 * @param gearRatio gear ratios 027 * @param trapezoidalLengthUnit units for trapezoidal motion length 028 * @param trapezoidalVelocityUnit units for trapezoidal motion velocityODO 029 * @param trapezoidalLimitsVelocity velocity limits for trapezoidal motion 030 * @param trapezoidalAccelerationUnit units for trapezoidal motion acceleration 031 * @param trapezoidalLimitsAcceleration acceleration limits for trapezoidal motion 032 * @param defaultTolerancesUnit default unit of the tolerance values 033 * @param defaultLowerTolerance default lower tolerance 034 * @param defaultUpperTolerance default upper tolerance 035 * @param feedForward feedforward constants 036 * @param simFeedForward simulated feedforward constants 037 * @param currentLimitsConfigs current limit configurations 038 * @param slot0 PID slot 0 configuration 039 * @param slot1 PID slot 1 configuration 040 * @param slot2 PID slot 2 configuration 041 * @param simSlot0 simulated PID slot 0 configuration 042 * @param simSlot1 simulated PID slot 1 configuration 043 * @param simSlot2 simulated PID slot 2 configuration 044 * @param mech2dDim dimensions of mechanical system 045 * @param rootName sim root name 046 * @param rootX sim root x coordinate 047 * @param rootY sim root y coordinate 048 * @param simNumLigaments number of simulated ligaments used 049 * @param rollerMOI moment of inertia for the roller 050 */ 051 public FlywheelConf( 052 String name, 053 Motors[] motorTypes, 054 int[] motorDeviceIDs, 055 String[] motorCanBus, 056 InvertedValue[] motorDirection, 057 NeutralModeValue[] motorEnabledBrakeMode, 058 NeutralModeValue[] motorDisabledBrakeMode, 059 int[][] gearRatio, 060 DistanceUnits trapezoidalLengthUnit, 061 VelocityUnits trapezoidalVelocityUnit, 062 double trapezoidalLimitsVelocity, 063 AccelerationUnits trapezoidalAccelerationUnit, 064 double trapezoidalLimitsAcceleration, 065 DistanceUnits defaultTolerancesUnit, 066 double defaultLowerTolerance, 067 double defaultUpperTolerance, 068 FeedforwardConstants feedForward, 069 FeedforwardConstants simFeedForward, 070 CurrentLimitsConfigs currentLimitsConfigs, 071 PIDSGVAConstants slot0, 072 PIDSGVAConstants slot1, 073 PIDSGVAConstants slot2, 074 PIDSGVAConstants simSlot0, 075 PIDSGVAConstants simSlot1, 076 PIDSGVAConstants simSlot2, 077 double mech2dDim, 078 String rootName, 079 double rootX, 080 double rootY, 081 int simNumLigaments, 082 double rollerMOI 083 084 ) { 085 super( 086 name, 087 motorTypes, 088 motorDeviceIDs, 089 motorCanBus, 090 motorDirection, 091 motorEnabledBrakeMode, 092 motorDisabledBrakeMode, 093 gearRatio, 094 trapezoidalLengthUnit, 095 VelocityUnits.ROTATIONS_PER_SECOND, 096 trapezoidalVelocityUnit.convertX( 097 trapezoidalLimitsVelocity, VelocityUnits.ROTATIONS_PER_SECOND 098 ), 099 AccelerationUnits.ROTATIONS_PER_SECOND2, 100 trapezoidalAccelerationUnit.convertX( 101 trapezoidalLimitsAcceleration, AccelerationUnits.ROTATIONS_PER_SECOND2 102 ), 103 DistanceUnits.ROTATION, 104 defaultTolerancesUnit.convertX(defaultLowerTolerance, DistanceUnits.ROTATION), 105 defaultTolerancesUnit.convertX(defaultUpperTolerance, DistanceUnits.ROTATION), 106 feedForward, 107 simFeedForward, 108 currentLimitsConfigs, 109 slot0, 110 slot1, 111 slot2, 112 simSlot0, 113 simSlot1, 114 simSlot2, 115 mech2dDim, 116 rootName, 117 rootX, 118 rootY, 119 simNumLigaments, 120 rollerMOI 121 ); 122 123 for (int i = 0; i < numMotors; i++) { 124 motorConfig[i].MotorOutput.PeakReverseDutyCycle = 0.0; 125 motorConfig[i].Voltage.PeakReverseVoltage = 0.0; 126 } 127 } 128}