diff --git a/C++/Config All/src/Configs.h b/C++/Config All/src/Configs.h index 5fdb7a88..8c76cb5c 100644 --- a/C++/Config All/src/Configs.h +++ b/C++/Config All/src/Configs.h @@ -11,16 +11,12 @@ struct configs { ctre::phoenix::sensors::PigeonIMUConfiguration _pigeon; ctre::phoenix::CANifierConfiguration _canifier; - + configs() { /*Construct all of the configurations with any set of values *These are just arbitrary values to demonstrate the feature */ - - - - //TalonSRX: _talon.primaryPID.selectedFeedbackSensor = FeedbackDevice::RemoteSensor0; _talon.primaryPID.selectedFeedbackCoefficient = 0.328293; @@ -28,10 +24,10 @@ struct configs { _talon.auxilaryPID.selectedFeedbackCoefficient = 0.877686; _talon.forwardLimitSwitchSource = LimitSwitchSource_Deactivated; _talon.reverseLimitSwitchSource = LimitSwitchSource_RemoteTalonSRX; - _talon.sum_0 = FeedbackDevice::QuadEncoder; //FeedbackDevice::PulseWidthEncodedPosition; - _talon.sum_1 = FeedbackDevice::RemoteSensor0; - _talon.diff_0 = FeedbackDevice::RemoteSensor1; - _talon.diff_1 = FeedbackDevice::PulseWidthEncodedPosition; + _talon.sum0Term = FeedbackDevice::QuadEncoder; //FeedbackDevice::PulseWidthEncodedPosition; + _talon.sum1Term = FeedbackDevice::RemoteSensor0; + _talon.diff0Term = FeedbackDevice::RemoteSensor1; + _talon.diff1Term = FeedbackDevice::PulseWidthEncodedPosition; _talon.peakCurrentLimit = 20; _talon.peakCurrentDuration = 200; _talon.continuousCurrentLimit = 30; @@ -54,47 +50,47 @@ struct configs { _talon.reverseSoftLimitThreshold = -1219; _talon.forwardSoftLimitEnable = true; _talon.reverseSoftLimitEnable = true; - _talon.slot_0.kP = 504.000000; - _talon.slot_0.kI = 5.600000; - _talon.slot_0.kD = 0.200000; - _talon.slot_0.kF = 19.300000; - _talon.slot_0.integralZone = 900; - _talon.slot_0.allowableClosedloopError = 217; - _talon.slot_0.maxIntegralAccumulator = 254.000000; - _talon.slot_0.closedLoopPeakOutput = 0.869990; - _talon.slot_0.closedLoopPeriod = 33; - _talon.slot_1.kP = 155.600000; - _talon.slot_1.kI = 5.560000; - _talon.slot_1.kD = 8.868600; - _talon.slot_1.kF = 454.000000; - _talon.slot_1.integralZone = 100; - _talon.slot_1.allowableClosedloopError = 200; - _talon.slot_1.maxIntegralAccumulator = 91.000000; - _talon.slot_1.closedLoopPeakOutput = 0.199413; - _talon.slot_1.closedLoopPeriod = 34; - _talon.slot_2.kP = 223.232000; - _talon.slot_2.kI = 34.000000; - _talon.slot_2.kD = 67.000000; - _talon.slot_2.kF = 6.323232; - _talon.slot_2.integralZone = 44; - _talon.slot_2.allowableClosedloopError = 343; - _talon.slot_2.maxIntegralAccumulator = 334.000000; - _talon.slot_2.closedLoopPeakOutput = 0.399804; - _talon.slot_2.closedLoopPeriod = 14; - _talon.slot_3.kP = 34.000000; - _talon.slot_3.kI = 32.000000; - _talon.slot_3.kD = 436.000000; - _talon.slot_3.kF = 0.343430; - _talon.slot_3.integralZone = 2323; - _talon.slot_3.allowableClosedloopError = 543; - _talon.slot_3.maxIntegralAccumulator = 687.000000; - _talon.slot_3.closedLoopPeakOutput = 0.129032; - _talon.slot_3.closedLoopPeriod = 12; + _talon.slot0.kP = 504.000000; + _talon.slot0.kI = 5.600000; + _talon.slot0.kD = 0.200000; + _talon.slot0.kF = 19.300000; + _talon.slot0.integralZone = 900; + _talon.slot0.allowableClosedloopError = 217; + _talon.slot0.maxIntegralAccumulator = 254.000000; + _talon.slot0.closedLoopPeakOutput = 0.869990; + _talon.slot0.closedLoopPeriod = 33; + _talon.slot1.kP = 155.600000; + _talon.slot1.kI = 5.560000; + _talon.slot1.kD = 8.868600; + _talon.slot1.kF = 454.000000; + _talon.slot1.integralZone = 100; + _talon.slot1.allowableClosedloopError = 200; + _talon.slot1.maxIntegralAccumulator = 91.000000; + _talon.slot1.closedLoopPeakOutput = 0.199413; + _talon.slot1.closedLoopPeriod = 34; + _talon.slot2.kP = 223.232000; + _talon.slot2.kI = 34.000000; + _talon.slot2.kD = 67.000000; + _talon.slot2.kF = 6.323232; + _talon.slot2.integralZone = 44; + _talon.slot2.allowableClosedloopError = 343; + _talon.slot2.maxIntegralAccumulator = 334.000000; + _talon.slot2.closedLoopPeakOutput = 0.399804; + _talon.slot2.closedLoopPeriod = 14; + _talon.slot3.kP = 34.000000; + _talon.slot3.kI = 32.000000; + _talon.slot3.kD = 436.000000; + _talon.slot3.kF = 0.343430; + _talon.slot3.integralZone = 2323; + _talon.slot3.allowableClosedloopError = 543; + _talon.slot3.maxIntegralAccumulator = 687.000000; + _talon.slot3.closedLoopPeakOutput = 0.129032; + _talon.slot3.closedLoopPeriod = 12; _talon.auxPIDPolarity = true; - _talon.filter_0.remoteSensorDeviceID = 22; - _talon.filter_0.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Roll; - _talon.filter_1.remoteSensorDeviceID = 41; - _talon.filter_1.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Yaw; + _talon.remoteFilter0.remoteSensorDeviceID = 22; + _talon.remoteFilter0.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Roll; + _talon.remoteFilter1.remoteSensorDeviceID = 41; + _talon.remoteFilter1.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Yaw; _talon.motionCruiseVelocity = 37; _talon.motionAcceleration = 3; _talon.motionProfileTrajectoryPeriod = 11; @@ -107,20 +103,20 @@ struct configs { _talon.softLimitDisableNeutralOnLOS = false; //true; _talon.pulseWidthPeriod_EdgesPerRot = 9; _talon.pulseWidthPeriod_FilterWindowSz = 32; - _talon.customParam_0 = 3; - _talon.customParam_1 = 5; - - //VictorSPX: + _talon.customParam0 = 3; + _talon.customParam1 = 5; + + //VictorSPX: _victor.primaryPID.selectedFeedbackSensor = RemoteFeedbackDevice::RemoteFeedbackDevice_SoftwareEmulatedSensor; _victor.primaryPID.selectedFeedbackCoefficient = 0.122208; _victor.auxilaryPID.selectedFeedbackSensor = RemoteFeedbackDevice::RemoteFeedbackDevice_SensorDifference; _victor.auxilaryPID.selectedFeedbackCoefficient = 0.290985; _victor.forwardLimitSwitchSource = RemoteLimitSwitchSource_RemoteTalonSRX; _victor.reverseLimitSwitchSource = RemoteLimitSwitchSource_Deactivated; - _victor.sum_0 = RemoteFeedbackDevice::RemoteFeedbackDevice_RemoteSensor0; - _victor.sum_1 = RemoteFeedbackDevice::RemoteFeedbackDevice_RemoteSensor1; - _victor.diff_0 = RemoteFeedbackDevice::RemoteFeedbackDevice_SoftwareEmulatedSensor; - _victor.diff_1 = RemoteFeedbackDevice::RemoteFeedbackDevice_RemoteSensor0; + _victor.sum0Term = RemoteFeedbackDevice::RemoteFeedbackDevice_RemoteSensor0; + _victor.sum1Term = RemoteFeedbackDevice::RemoteFeedbackDevice_RemoteSensor1; + _victor.diff0Term = RemoteFeedbackDevice::RemoteFeedbackDevice_SoftwareEmulatedSensor; + _victor.diff1Term = RemoteFeedbackDevice::RemoteFeedbackDevice_RemoteSensor0; _victor.openloopRamp = 0.300882; _victor.closedloopRamp = 0.100294; _victor.peakOutputForward = 0.659824; @@ -140,47 +136,47 @@ struct configs { _victor.reverseSoftLimitThreshold = -9023; _victor.forwardSoftLimitEnable = false; //true; _victor.reverseSoftLimitEnable = true; - _victor.slot_0.kP = 0.100000; - _victor.slot_0.kI = 0.010000; - _victor.slot_0.kD = 0.050000; - _victor.slot_0.kF = 0.320000; - _victor.slot_0.integralZone = 900; - _victor.slot_0.allowableClosedloopError = 124; - _victor.slot_0.maxIntegralAccumulator = 22.000000; - _victor.slot_0.closedLoopPeakOutput = 0.599218; - _victor.slot_0.closedLoopPeriod = 33; - _victor.slot_1.kP = 0.400000; - _victor.slot_1.kI = 0.300000; - _victor.slot_1.kD = 0.100000; - _victor.slot_1.kF = 0.923000; - _victor.slot_1.integralZone = 90; - _victor.slot_1.allowableClosedloopError = 21; - _victor.slot_1.maxIntegralAccumulator = 54.000000; - _victor.slot_1.closedLoopPeakOutput = 0.399804; - _victor.slot_1.closedLoopPeriod = 23; - _victor.slot_2.kP = 2.200000; - _victor.slot_2.kI = 0.670000; - _victor.slot_2.kD = 9.232000; - _victor.slot_2.kF = 1.121000; - _victor.slot_2.integralZone = 19; - _victor.slot_2.allowableClosedloopError = 190; - _victor.slot_2.maxIntegralAccumulator = 37.000000; - _victor.slot_2.closedLoopPeakOutput = 0.299120; - _victor.slot_2.closedLoopPeriod = 9; - _victor.slot_3.kP = 10.000000; - _victor.slot_3.kI = 11.000000; - _victor.slot_3.kD = 12.000000; - _victor.slot_3.kF = 13.000000; - _victor.slot_3.integralZone = 654; - _victor.slot_3.allowableClosedloopError = 557; - _victor.slot_3.maxIntegralAccumulator = 342.000000; - _victor.slot_3.closedLoopPeakOutput = 0.899316; - _victor.slot_3.closedLoopPeriod = 21; + _victor.slot0.kP = 0.100000; + _victor.slot0.kI = 0.010000; + _victor.slot0.kD = 0.050000; + _victor.slot0.kF = 0.320000; + _victor.slot0.integralZone = 900; + _victor.slot0.allowableClosedloopError = 124; + _victor.slot0.maxIntegralAccumulator = 22.000000; + _victor.slot0.closedLoopPeakOutput = 0.599218; + _victor.slot0.closedLoopPeriod = 33; + _victor.slot1.kP = 0.400000; + _victor.slot1.kI = 0.300000; + _victor.slot1.kD = 0.100000; + _victor.slot1.kF = 0.923000; + _victor.slot1.integralZone = 90; + _victor.slot1.allowableClosedloopError = 21; + _victor.slot1.maxIntegralAccumulator = 54.000000; + _victor.slot1.closedLoopPeakOutput = 0.399804; + _victor.slot1.closedLoopPeriod = 23; + _victor.slot2.kP = 2.200000; + _victor.slot2.kI = 0.670000; + _victor.slot2.kD = 9.232000; + _victor.slot2.kF = 1.121000; + _victor.slot2.integralZone = 19; + _victor.slot2.allowableClosedloopError = 190; + _victor.slot2.maxIntegralAccumulator = 37.000000; + _victor.slot2.closedLoopPeakOutput = 0.299120; + _victor.slot2.closedLoopPeriod = 9; + _victor.slot3.kP = 10.000000; + _victor.slot3.kI = 11.000000; + _victor.slot3.kD = 12.000000; + _victor.slot3.kF = 13.000000; + _victor.slot3.integralZone = 654; + _victor.slot3.allowableClosedloopError = 557; + _victor.slot3.maxIntegralAccumulator = 342.000000; + _victor.slot3.closedLoopPeakOutput = 0.899316; + _victor.slot3.closedLoopPeriod = 21; _victor.auxPIDPolarity = true; - _victor.filter_0.remoteSensorDeviceID = 22; - _victor.filter_0.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Roll; - _victor.filter_1.remoteSensorDeviceID = 41; - _victor.filter_1.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Yaw; + _victor.remoteFilter0.remoteSensorDeviceID = 22; + _victor.remoteFilter0.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Roll; + _victor.remoteFilter1.remoteSensorDeviceID = 41; + _victor.remoteFilter1.remoteSensorSource = RemoteSensorSource::RemoteSensorSource_GadgeteerPigeon_Yaw; _victor.motionCruiseVelocity = 50; _victor.motionAcceleration = 3; _victor.motionProfileTrajectoryPeriod = 20; @@ -193,24 +189,24 @@ struct configs { _victor.softLimitDisableNeutralOnLOS = true; _victor.pulseWidthPeriod_EdgesPerRot = 8; _victor.pulseWidthPeriod_FilterWindowSz = 19; - _victor.customParam_0 = 7; - _victor.customParam_1 = 9; - - + _victor.customParam0 = 7; + _victor.customParam1 = 9; + + //PigeonIMU: - _pigeon.customParam_0 = 6; - _pigeon.customParam_1 = 14; - + _pigeon.customParam0 = 6; + _pigeon.customParam1 = 14; + //CANifier _canifier.velocityMeasurementPeriod = CANifierVelocityMeasPeriod::Period_50Ms; _canifier.velocityMeasurementWindow = 8; _canifier.clearPositionOnLimitF = true; _canifier.clearPositionOnLimitR = false; //true; _canifier.clearPositionOnQuadIdx = true; - _canifier.customParam_0 = 2; - _canifier.customParam_1 = 1; - + _canifier.customParam0 = 2; + _canifier.customParam1 = 1; + } }; - + #endif /* SRC_CONFIGS_H_ */ diff --git a/C++/Config All/src/Robot.cpp b/C++/Config All/src/Robot.cpp index ba131621..4f4e4e80 100644 --- a/C++/Config All/src/Robot.cpp +++ b/C++/Config All/src/Robot.cpp @@ -3,8 +3,8 @@ #include /* This project may be used to test the GetAllConfigs, ConfigAllSettings, and ConfigFactoryDefault - * Functions. Note that this project requires at least firmware 3.11 on Victors/Talons - * for full function. Also, if firmware greater than 0.41 on the pigeon and 0.42 on the canfier + * Functions. Note that this project requires at least firmware 3.10/11.10 on Victors/Talons + * for full function. Also, if firmware greater than 0.41 on the pigeon and 0.42 on the canifier * isn't used, the pigeon/canifier won't retain configs on reboot. * Some recommended tests: * 1. Set to custom configs and then read configs. Confirm that read and write are the same. @@ -16,7 +16,7 @@ class Robot: public IterativeRobot { private: - TalonSRX * _talon = new TalonSRX(23); + TalonSRX * _talon = new TalonSRX(1); VictorSPX * _victor = new VictorSPX(2); PigeonIMU * _pigeon = new PigeonIMU(3); CANifier * _canifier = new CANifier(4); diff --git a/Java/Config All/src/org/usfirst/frc/team217/robot/Configs.java b/Java/Config All/src/org/usfirst/frc/team217/robot/Configs.java index 4879a665..89c80b6b 100644 --- a/Java/Config All/src/org/usfirst/frc/team217/robot/Configs.java +++ b/Java/Config All/src/org/usfirst/frc/team217/robot/Configs.java @@ -37,10 +37,10 @@ public Configs() _talon.auxilaryPID.selectedFeedbackCoefficient = 0.877686; _talon.forwardLimitSwitchSource = LimitSwitchSource.Deactivated; _talon.reverseLimitSwitchSource = LimitSwitchSource.RemoteTalonSRX; - _talon.sum_0 = FeedbackDevice.QuadEncoder; //FeedbackDevice.PulseWidthEncodedPosition; - _talon.sum_1 = FeedbackDevice.RemoteSensor0; - _talon.diff_0 = FeedbackDevice.RemoteSensor1; - _talon.diff_1 = FeedbackDevice.PulseWidthEncodedPosition; + _talon.sum0Term = FeedbackDevice.QuadEncoder; //FeedbackDevice.PulseWidthEncodedPosition; + _talon.sum1Term = FeedbackDevice.RemoteSensor0; + _talon.diff0Term = FeedbackDevice.RemoteSensor1; + _talon.diff1Term = FeedbackDevice.PulseWidthEncodedPosition; _talon.peakCurrentLimit = 20; _talon.peakCurrentDuration = 200; _talon.continuousCurrentLimit = 30; @@ -63,47 +63,47 @@ public Configs() _talon.reverseSoftLimitThreshold = -1219; _talon.forwardSoftLimitEnable = true; _talon.reverseSoftLimitEnable = true; - _talon.slot_0.kP = 504.000000; - _talon.slot_0.kI = 5.600000; - _talon.slot_0.kD = 0.200000; - _talon.slot_0.kF = 19.300000; - _talon.slot_0.integralZone = 900; - _talon.slot_0.allowableClosedloopError = 217; - _talon.slot_0.maxIntegralAccumulator = 254.000000; - _talon.slot_0.closedLoopPeakOutput = 0.869990; - _talon.slot_0.closedLoopPeriod = 33; - _talon.slot_1.kP = 155.600000; - _talon.slot_1.kI = 5.560000; - _talon.slot_1.kD = 8.868600; - _talon.slot_1.kF = 454.000000; - _talon.slot_1.integralZone = 100; - _talon.slot_1.allowableClosedloopError = 200; - _talon.slot_1.maxIntegralAccumulator = 91.000000; - _talon.slot_1.closedLoopPeakOutput = 0.199413; - _talon.slot_1.closedLoopPeriod = 34; - _talon.slot_2.kP = 223.232000; - _talon.slot_2.kI = 34.000000; - _talon.slot_2.kD = 67.000000; - _talon.slot_2.kF = 6.323232; - _talon.slot_2.integralZone = 44; - _talon.slot_2.allowableClosedloopError = 343; - _talon.slot_2.maxIntegralAccumulator = 334.000000; - _talon.slot_2.closedLoopPeakOutput = 0.399804; - _talon.slot_2.closedLoopPeriod = 14; - _talon.slot_3.kP = 34.000000; - _talon.slot_3.kI = 32.000000; - _talon.slot_3.kD = 436.000000; - _talon.slot_3.kF = 0.343430; - _talon.slot_3.integralZone = 2323; - _talon.slot_3.allowableClosedloopError = 543; - _talon.slot_3.maxIntegralAccumulator = 687.000000; - _talon.slot_3.closedLoopPeakOutput = 0.129032; - _talon.slot_3.closedLoopPeriod = 12; + _talon.slot0.kP = 504.000000; + _talon.slot0.kI = 5.600000; + _talon.slot0.kD = 0.200000; + _talon.slot0.kF = 19.300000; + _talon.slot0.integralZone = 900; + _talon.slot0.allowableClosedloopError = 217; + _talon.slot0.maxIntegralAccumulator = 254.000000; + _talon.slot0.closedLoopPeakOutput = 0.869990; + _talon.slot0.closedLoopPeriod = 33; + _talon.slot1.kP = 155.600000; + _talon.slot1.kI = 5.560000; + _talon.slot1.kD = 8.868600; + _talon.slot1.kF = 454.000000; + _talon.slot1.integralZone = 100; + _talon.slot1.allowableClosedloopError = 200; + _talon.slot1.maxIntegralAccumulator = 91.000000; + _talon.slot1.closedLoopPeakOutput = 0.199413; + _talon.slot1.closedLoopPeriod = 34; + _talon.slot2.kP = 223.232000; + _talon.slot2.kI = 34.000000; + _talon.slot2.kD = 67.000000; + _talon.slot2.kF = 6.323232; + _talon.slot2.integralZone = 44; + _talon.slot2.allowableClosedloopError = 343; + _talon.slot2.maxIntegralAccumulator = 334.000000; + _talon.slot2.closedLoopPeakOutput = 0.399804; + _talon.slot2.closedLoopPeriod = 14; + _talon.slot3.kP = 34.000000; + _talon.slot3.kI = 32.000000; + _talon.slot3.kD = 436.000000; + _talon.slot3.kF = 0.343430; + _talon.slot3.integralZone = 2323; + _talon.slot3.allowableClosedloopError = 543; + _talon.slot3.maxIntegralAccumulator = 687.000000; + _talon.slot3.closedLoopPeakOutput = 0.129032; + _talon.slot3.closedLoopPeriod = 12; _talon.auxPIDPolarity = true; - _talon.filter_0.remoteSensorDeviceID = 22; - _talon.filter_0.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Roll; - _talon.filter_1.remoteSensorDeviceID = 41; - _talon.filter_1.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Yaw; + _talon.remoteFilter0.remoteSensorDeviceID = 22; + _talon.remoteFilter0.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Roll; + _talon.remoteFilter1.remoteSensorDeviceID = 41; + _talon.remoteFilter1.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Yaw; _talon.motionCruiseVelocity = 37; _talon.motionAcceleration = 3; _talon.motionProfileTrajectoryPeriod = 11; @@ -116,8 +116,8 @@ public Configs() _talon.softLimitDisableNeutralOnLOS = false; //true; _talon.pulseWidthPeriod_EdgesPerRot = 9; _talon.pulseWidthPeriod_FilterWindowSz = 32; - _talon.customParam_0 = 3; - _talon.customParam_1 = 5; + _talon.customParam0 = 3; + _talon.customParam1 = 5; //VictorSPX: _victor.primaryPID.selectedFeedbackSensor = RemoteFeedbackDevice.SoftwareEmulatedSensor; @@ -126,10 +126,10 @@ public Configs() _victor.auxilaryPID.selectedFeedbackCoefficient = 0.290985; _victor.forwardLimitSwitchSource = RemoteLimitSwitchSource.RemoteTalonSRX; _victor.reverseLimitSwitchSource = RemoteLimitSwitchSource.Deactivated; - _victor.sum_0 = RemoteFeedbackDevice.RemoteSensor0; - _victor.sum_1 = RemoteFeedbackDevice.RemoteSensor1; - _victor.diff_0 = RemoteFeedbackDevice.SoftwareEmulatedSensor; - _victor.diff_1 = RemoteFeedbackDevice.RemoteSensor0; + _victor.sum0Term = RemoteFeedbackDevice.RemoteSensor0; + _victor.sum1Term = RemoteFeedbackDevice.RemoteSensor1; + _victor.diff0Term = RemoteFeedbackDevice.SoftwareEmulatedSensor; + _victor.diff1Term = RemoteFeedbackDevice.RemoteSensor0; _victor.openloopRamp = 0.300882; _victor.closedloopRamp = 0.100294; _victor.peakOutputForward = 0.659824; @@ -149,47 +149,47 @@ public Configs() _victor.reverseSoftLimitThreshold = -9023; _victor.forwardSoftLimitEnable = false; //true; _victor.reverseSoftLimitEnable = true; - _victor.slot_0.kP = 0.100000; - _victor.slot_0.kI = 0.010000; - _victor.slot_0.kD = 0.050000; - _victor.slot_0.kF = 0.320000; - _victor.slot_0.integralZone = 900; - _victor.slot_0.allowableClosedloopError = 124; - _victor.slot_0.maxIntegralAccumulator = 22.000000; - _victor.slot_0.closedLoopPeakOutput = 0.599218; - _victor.slot_0.closedLoopPeriod = 33; - _victor.slot_1.kP = 0.400000; - _victor.slot_1.kI = 0.300000; - _victor.slot_1.kD = 0.100000; - _victor.slot_1.kF = 0.923000; - _victor.slot_1.integralZone = 90; - _victor.slot_1.allowableClosedloopError = 21; - _victor.slot_1.maxIntegralAccumulator = 54.000000; - _victor.slot_1.closedLoopPeakOutput = 0.399804; - _victor.slot_1.closedLoopPeriod = 23; - _victor.slot_2.kP = 2.200000; - _victor.slot_2.kI = 0.670000; - _victor.slot_2.kD = 9.232000; - _victor.slot_2.kF = 1.121000; - _victor.slot_2.integralZone = 19; - _victor.slot_2.allowableClosedloopError = 190; - _victor.slot_2.maxIntegralAccumulator = 37.000000; - _victor.slot_2.closedLoopPeakOutput = 0.299120; - _victor.slot_2.closedLoopPeriod = 9; - _victor.slot_3.kP = 10.000000; - _victor.slot_3.kI = 11.000000; - _victor.slot_3.kD = 12.000000; - _victor.slot_3.kF = 13.000000; - _victor.slot_3.integralZone = 654; - _victor.slot_3.allowableClosedloopError = 557; - _victor.slot_3.maxIntegralAccumulator = 342.000000; - _victor.slot_3.closedLoopPeakOutput = 0.899316; - _victor.slot_3.closedLoopPeriod = 21; + _victor.slot0.kP = 0.100000; + _victor.slot0.kI = 0.010000; + _victor.slot0.kD = 0.050000; + _victor.slot0.kF = 0.320000; + _victor.slot0.integralZone = 900; + _victor.slot0.allowableClosedloopError = 124; + _victor.slot0.maxIntegralAccumulator = 22.000000; + _victor.slot0.closedLoopPeakOutput = 0.599218; + _victor.slot0.closedLoopPeriod = 33; + _victor.slot1.kP = 0.400000; + _victor.slot1.kI = 0.300000; + _victor.slot1.kD = 0.100000; + _victor.slot1.kF = 0.923000; + _victor.slot1.integralZone = 90; + _victor.slot1.allowableClosedloopError = 21; + _victor.slot1.maxIntegralAccumulator = 54.000000; + _victor.slot1.closedLoopPeakOutput = 0.399804; + _victor.slot1.closedLoopPeriod = 23; + _victor.slot2.kP = 2.200000; + _victor.slot2.kI = 0.670000; + _victor.slot2.kD = 9.232000; + _victor.slot2.kF = 1.121000; + _victor.slot2.integralZone = 19; + _victor.slot2.allowableClosedloopError = 190; + _victor.slot2.maxIntegralAccumulator = 37.000000; + _victor.slot2.closedLoopPeakOutput = 0.299120; + _victor.slot2.closedLoopPeriod = 9; + _victor.slot3.kP = 10.000000; + _victor.slot3.kI = 11.000000; + _victor.slot3.kD = 12.000000; + _victor.slot3.kF = 13.000000; + _victor.slot3.integralZone = 654; + _victor.slot3.allowableClosedloopError = 557; + _victor.slot3.maxIntegralAccumulator = 342.000000; + _victor.slot3.closedLoopPeakOutput = 0.899316; + _victor.slot3.closedLoopPeriod = 21; _victor.auxPIDPolarity = true; - _victor.filter_0.remoteSensorDeviceID = 22; - _victor.filter_0.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Roll; - _victor.filter_1.remoteSensorDeviceID = 41; - _victor.filter_1.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Yaw; + _victor.remoteFilter0.remoteSensorDeviceID = 22; + _victor.remoteFilter0.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Roll; + _victor.remoteFilter1.remoteSensorDeviceID = 41; + _victor.remoteFilter1.remoteSensorSource = RemoteSensorSource.GadgeteerPigeon_Yaw; _victor.motionCruiseVelocity = 50; _victor.motionAcceleration = 3; _victor.motionProfileTrajectoryPeriod = 20; @@ -202,13 +202,13 @@ public Configs() _victor.softLimitDisableNeutralOnLOS = true; _victor.pulseWidthPeriod_EdgesPerRot = 8; _victor.pulseWidthPeriod_FilterWindowSz = 19; - _victor.customParam_0 = 7; - _victor.customParam_1 = 9; + _victor.customParam0 = 7; + _victor.customParam1 = 9; //PigeonIMU: - _pigeon.customParam_0 = 6; - _pigeon.customParam_1 = 14; + _pigeon.customParam0 = 6; + _pigeon.customParam1 = 14; //CANifier _canifier.velocityMeasurementPeriod = VelocityPeriod.Period_50Ms; @@ -216,8 +216,8 @@ public Configs() _canifier.clearPositionOnLimitF = true; _canifier.clearPositionOnLimitR = false; //true; _canifier.clearPositionOnQuadIdx = true; - _canifier.customParam_0 = 2; - _canifier.customParam_1 = 1; + _canifier.customParam0 = 2; + _canifier.customParam1 = 1; } } diff --git a/Java/Config All/src/org/usfirst/frc/team217/robot/Robot.java b/Java/Config All/src/org/usfirst/frc/team217/robot/Robot.java index f87a32a4..6ec29e1d 100644 --- a/Java/Config All/src/org/usfirst/frc/team217/robot/Robot.java +++ b/Java/Config All/src/org/usfirst/frc/team217/robot/Robot.java @@ -8,7 +8,7 @@ import edu.wpi.first.wpilibj.Joystick; /* This project may be used to test the getAllConfigs, configAllSettings, and configFactoryDefault - * Functions. Note that this project requires at least firmware 3.11 on Victors/Talons + * Functions. Note that this project requires at least firmware 3.10/11.10 on Victors/Talons * for full function. Also, if firmware greater than 0.41 on the pigeon and 0.42 on the canfier * isn't used, the pigeon/canifier won't retain configs on reboot. * Some recommended tests: @@ -22,7 +22,7 @@ public class Robot extends IterativeRobot { /** make a talon with deviceId 0 */ - TalonSRX _talon = new TalonSRX(23); + TalonSRX _talon = new TalonSRX(1); VictorSPX _victor = new VictorSPX(2); PigeonIMU _pigeon = new PigeonIMU(3); CANifier _canifier = new CANifier(4);