001/* 002 * Copyright (C) Cross The Road Electronics. All rights reserved. 003 * License information can be found in CTRE_LICENSE.txt 004 * For support and suggestions contact support@ctr-electronics.com or file 005 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases 006 */ 007package com.ctre.phoenix6.configs; 008 009import com.ctre.phoenix6.StatusCode; 010 011/** 012 * Class description for the Talon FX integrated motor controller. 013 * 014 * This handles the configurations for the {@link com.ctre.phoenix6.hardware.TalonFX} 015 */ 016public class TalonFXConfiguration implements ParentConfiguration 017{ 018 /** 019 * True if we should factory default newer unsupported configs, 020 * false to leave newer unsupported configs alone. 021 * <p> 022 * This flag addresses a corner case where the device may have 023 * firmware with newer configs that didn't exist when this 024 * version of the API was built. If this occurs and this 025 * flag is true, unsupported new configs will be factory 026 * defaulted to avoid unexpected behavior. 027 * <p> 028 * This is also the behavior in Phoenix 5, so this flag 029 * is defaulted to true to match. 030 */ 031 public boolean FutureProofConfigs = true; 032 033 034 /** 035 * Configs that directly affect motor output. 036 * <p> 037 * Includes motor invert, neutral mode, and other features related to 038 * motor output. 039 * <p> 040 * Parameter list: 041 * 042 * <ul> 043 * <li> {@link MotorOutputConfigs#Inverted} 044 * <li> {@link MotorOutputConfigs#NeutralMode} 045 * <li> {@link MotorOutputConfigs#DutyCycleNeutralDeadband} 046 * <li> {@link MotorOutputConfigs#PeakForwardDutyCycle} 047 * <li> {@link MotorOutputConfigs#PeakReverseDutyCycle} 048 * <li> {@link MotorOutputConfigs#ControlTimesyncFreqHz} 049 * </ul> 050 * 051 */ 052 public MotorOutputConfigs MotorOutput = new MotorOutputConfigs(); 053 054 /** 055 * Configs that directly affect current limiting features. 056 * <p> 057 * Contains the supply/stator current limit thresholds and whether to 058 * enable them. 059 * <p> 060 * Parameter list: 061 * 062 * <ul> 063 * <li> {@link CurrentLimitsConfigs#StatorCurrentLimit} 064 * <li> {@link CurrentLimitsConfigs#StatorCurrentLimitEnable} 065 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLimit} 066 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLimitEnable} 067 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLowerLimit} 068 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLowerTime} 069 * </ul> 070 * 071 */ 072 public CurrentLimitsConfigs CurrentLimits = new CurrentLimitsConfigs(); 073 074 /** 075 * Configs that affect Voltage control types. 076 * <p> 077 * Includes peak output voltages and other configs affecting voltage 078 * measurements. 079 * <p> 080 * Parameter list: 081 * 082 * <ul> 083 * <li> {@link VoltageConfigs#SupplyVoltageTimeConstant} 084 * <li> {@link VoltageConfigs#PeakForwardVoltage} 085 * <li> {@link VoltageConfigs#PeakReverseVoltage} 086 * </ul> 087 * 088 */ 089 public VoltageConfigs Voltage = new VoltageConfigs(); 090 091 /** 092 * Configs that affect Torque Current control types. 093 * <p> 094 * Includes the maximum and minimum applied torque output and the 095 * neutral deadband used during TorqueCurrentFOC requests. 096 * <p> 097 * Parameter list: 098 * 099 * <ul> 100 * <li> {@link TorqueCurrentConfigs#PeakForwardTorqueCurrent} 101 * <li> {@link TorqueCurrentConfigs#PeakReverseTorqueCurrent} 102 * <li> {@link TorqueCurrentConfigs#TorqueNeutralDeadband} 103 * </ul> 104 * 105 */ 106 public TorqueCurrentConfigs TorqueCurrent = new TorqueCurrentConfigs(); 107 108 /** 109 * Configs that affect the feedback of this motor controller. 110 * <p> 111 * Includes feedback sensor source, any offsets for the feedback 112 * sensor, and various ratios to describe the relationship between the 113 * sensor and the mechanism for closed looping. 114 * <p> 115 * Parameter list: 116 * 117 * <ul> 118 * <li> {@link FeedbackConfigs#FeedbackRotorOffset} 119 * <li> {@link FeedbackConfigs#SensorToMechanismRatio} 120 * <li> {@link FeedbackConfigs#RotorToSensorRatio} 121 * <li> {@link FeedbackConfigs#FeedbackSensorSource} 122 * <li> {@link FeedbackConfigs#FeedbackRemoteSensorID} 123 * <li> {@link FeedbackConfigs#VelocityFilterTimeConstant} 124 * </ul> 125 * 126 */ 127 public FeedbackConfigs Feedback = new FeedbackConfigs(); 128 129 /** 130 * Configs related to sensors used for differential control of a 131 * mechanism. 132 * <p> 133 * Includes the differential sensor sources and IDs. 134 * <p> 135 * Parameter list: 136 * 137 * <ul> 138 * <li> {@link DifferentialSensorsConfigs#DifferentialSensorSource} 139 * <li> {@link 140 * DifferentialSensorsConfigs#DifferentialTalonFXSensorID} 141 * <li> {@link 142 * DifferentialSensorsConfigs#DifferentialRemoteSensorID} 143 * </ul> 144 * 145 */ 146 public DifferentialSensorsConfigs DifferentialSensors = new DifferentialSensorsConfigs(); 147 148 /** 149 * Configs related to constants used for differential control of a 150 * mechanism. 151 * <p> 152 * Includes the differential peak outputs. 153 * <p> 154 * Parameter list: 155 * 156 * <ul> 157 * <li> {@link 158 * DifferentialConstantsConfigs#PeakDifferentialDutyCycle} 159 * <li> {@link DifferentialConstantsConfigs#PeakDifferentialVoltage} 160 * <li> {@link 161 * DifferentialConstantsConfigs#PeakDifferentialTorqueCurrent} 162 * </ul> 163 * 164 */ 165 public DifferentialConstantsConfigs DifferentialConstants = new DifferentialConstantsConfigs(); 166 167 /** 168 * Configs that affect the open-loop control of this motor controller. 169 * <p> 170 * Open-loop ramp rates for the various control types. 171 * <p> 172 * Parameter list: 173 * 174 * <ul> 175 * <li> {@link OpenLoopRampsConfigs#DutyCycleOpenLoopRampPeriod} 176 * <li> {@link OpenLoopRampsConfigs#VoltageOpenLoopRampPeriod} 177 * <li> {@link OpenLoopRampsConfigs#TorqueOpenLoopRampPeriod} 178 * </ul> 179 * 180 */ 181 public OpenLoopRampsConfigs OpenLoopRamps = new OpenLoopRampsConfigs(); 182 183 /** 184 * Configs that affect the closed-loop control of this motor 185 * controller. 186 * <p> 187 * Closed-loop ramp rates for the various control types. 188 * <p> 189 * Parameter list: 190 * 191 * <ul> 192 * <li> {@link ClosedLoopRampsConfigs#DutyCycleClosedLoopRampPeriod} 193 * <li> {@link ClosedLoopRampsConfigs#VoltageClosedLoopRampPeriod} 194 * <li> {@link ClosedLoopRampsConfigs#TorqueClosedLoopRampPeriod} 195 * </ul> 196 * 197 */ 198 public ClosedLoopRampsConfigs ClosedLoopRamps = new ClosedLoopRampsConfigs(); 199 200 /** 201 * Configs that change how the motor controller behaves under 202 * different limit switch states. 203 * <p> 204 * Includes configs such as enabling limit switches, configuring the 205 * remote sensor ID, the source, and the position to set on limit. 206 * <p> 207 * Parameter list: 208 * 209 * <ul> 210 * <li> {@link HardwareLimitSwitchConfigs#ForwardLimitType} 211 * <li> {@link 212 * HardwareLimitSwitchConfigs#ForwardLimitAutosetPositionEnable} 213 * <li> {@link 214 * HardwareLimitSwitchConfigs#ForwardLimitAutosetPositionValue} 215 * <li> {@link HardwareLimitSwitchConfigs#ForwardLimitEnable} 216 * <li> {@link HardwareLimitSwitchConfigs#ForwardLimitSource} 217 * <li> {@link 218 * HardwareLimitSwitchConfigs#ForwardLimitRemoteSensorID} 219 * <li> {@link HardwareLimitSwitchConfigs#ReverseLimitType} 220 * <li> {@link 221 * HardwareLimitSwitchConfigs#ReverseLimitAutosetPositionEnable} 222 * <li> {@link 223 * HardwareLimitSwitchConfigs#ReverseLimitAutosetPositionValue} 224 * <li> {@link HardwareLimitSwitchConfigs#ReverseLimitEnable} 225 * <li> {@link HardwareLimitSwitchConfigs#ReverseLimitSource} 226 * <li> {@link 227 * HardwareLimitSwitchConfigs#ReverseLimitRemoteSensorID} 228 * </ul> 229 * 230 */ 231 public HardwareLimitSwitchConfigs HardwareLimitSwitch = new HardwareLimitSwitchConfigs(); 232 233 /** 234 * Configs that affect audible components of the device. 235 * <p> 236 * Includes configuration for the beep on boot. 237 * <p> 238 * Parameter list: 239 * 240 * <ul> 241 * <li> {@link AudioConfigs#BeepOnBoot} 242 * <li> {@link AudioConfigs#BeepOnConfig} 243 * <li> {@link AudioConfigs#AllowMusicDurDisable} 244 * </ul> 245 * 246 */ 247 public AudioConfigs Audio = new AudioConfigs(); 248 249 /** 250 * Configs that affect how software-limit switches behave. 251 * <p> 252 * Includes enabling software-limit switches and the threshold at 253 * which they are tripped. 254 * <p> 255 * Parameter list: 256 * 257 * <ul> 258 * <li> {@link SoftwareLimitSwitchConfigs#ForwardSoftLimitEnable} 259 * <li> {@link SoftwareLimitSwitchConfigs#ReverseSoftLimitEnable} 260 * <li> {@link SoftwareLimitSwitchConfigs#ForwardSoftLimitThreshold} 261 * <li> {@link SoftwareLimitSwitchConfigs#ReverseSoftLimitThreshold} 262 * </ul> 263 * 264 */ 265 public SoftwareLimitSwitchConfigs SoftwareLimitSwitch = new SoftwareLimitSwitchConfigs(); 266 267 /** 268 * Configs for Motion MagicĀ®. 269 * <p> 270 * Includes Velocity, Acceleration, Jerk, and Expo parameters. 271 * <p> 272 * Parameter list: 273 * 274 * <ul> 275 * <li> {@link MotionMagicConfigs#MotionMagicCruiseVelocity} 276 * <li> {@link MotionMagicConfigs#MotionMagicAcceleration} 277 * <li> {@link MotionMagicConfigs#MotionMagicJerk} 278 * <li> {@link MotionMagicConfigs#MotionMagicExpo_kV} 279 * <li> {@link MotionMagicConfigs#MotionMagicExpo_kA} 280 * </ul> 281 * 282 */ 283 public MotionMagicConfigs MotionMagic = new MotionMagicConfigs(); 284 285 /** 286 * Custom Params. 287 * <p> 288 * Custom paramaters that have no real impact on controller. 289 * <p> 290 * Parameter list: 291 * 292 * <ul> 293 * <li> {@link CustomParamsConfigs#CustomParam0} 294 * <li> {@link CustomParamsConfigs#CustomParam1} 295 * </ul> 296 * 297 */ 298 public CustomParamsConfigs CustomParams = new CustomParamsConfigs(); 299 300 /** 301 * Configs that affect general behavior during closed-looping. 302 * <p> 303 * Includes Continuous Wrap features. 304 * <p> 305 * Parameter list: 306 * 307 * <ul> 308 * <li> {@link ClosedLoopGeneralConfigs#ContinuousWrap} 309 * </ul> 310 * 311 */ 312 public ClosedLoopGeneralConfigs ClosedLoopGeneral = new ClosedLoopGeneralConfigs(); 313 314 /** 315 * Gains for the specified slot. 316 * <p> 317 * If this slot is selected, these gains are used in closed loop 318 * control requests. 319 * <p> 320 * Parameter list: 321 * 322 * <ul> 323 * <li> {@link Slot0Configs#kP} 324 * <li> {@link Slot0Configs#kI} 325 * <li> {@link Slot0Configs#kD} 326 * <li> {@link Slot0Configs#kS} 327 * <li> {@link Slot0Configs#kV} 328 * <li> {@link Slot0Configs#kA} 329 * <li> {@link Slot0Configs#kG} 330 * <li> {@link Slot0Configs#GravityType} 331 * <li> {@link Slot0Configs#StaticFeedforwardSign} 332 * </ul> 333 * 334 */ 335 public Slot0Configs Slot0 = new Slot0Configs(); 336 337 /** 338 * Gains for the specified slot. 339 * <p> 340 * If this slot is selected, these gains are used in closed loop 341 * control requests. 342 * <p> 343 * Parameter list: 344 * 345 * <ul> 346 * <li> {@link Slot1Configs#kP} 347 * <li> {@link Slot1Configs#kI} 348 * <li> {@link Slot1Configs#kD} 349 * <li> {@link Slot1Configs#kS} 350 * <li> {@link Slot1Configs#kV} 351 * <li> {@link Slot1Configs#kA} 352 * <li> {@link Slot1Configs#kG} 353 * <li> {@link Slot1Configs#GravityType} 354 * <li> {@link Slot1Configs#StaticFeedforwardSign} 355 * </ul> 356 * 357 */ 358 public Slot1Configs Slot1 = new Slot1Configs(); 359 360 /** 361 * Gains for the specified slot. 362 * <p> 363 * If this slot is selected, these gains are used in closed loop 364 * control requests. 365 * <p> 366 * Parameter list: 367 * 368 * <ul> 369 * <li> {@link Slot2Configs#kP} 370 * <li> {@link Slot2Configs#kI} 371 * <li> {@link Slot2Configs#kD} 372 * <li> {@link Slot2Configs#kS} 373 * <li> {@link Slot2Configs#kV} 374 * <li> {@link Slot2Configs#kA} 375 * <li> {@link Slot2Configs#kG} 376 * <li> {@link Slot2Configs#GravityType} 377 * <li> {@link Slot2Configs#StaticFeedforwardSign} 378 * </ul> 379 * 380 */ 381 public Slot2Configs Slot2 = new Slot2Configs(); 382 383 /** 384 * Modifies this configuration's MotorOutput parameter and returns itself for 385 * method-chaining and easier to use config API. 386 * <p> 387 * Configs that directly affect motor output. 388 * <p> 389 * Includes motor invert, neutral mode, and other features related to 390 * motor output. 391 * <p> 392 * Parameter list: 393 * 394 * <ul> 395 * <li> {@link MotorOutputConfigs#Inverted} 396 * <li> {@link MotorOutputConfigs#NeutralMode} 397 * <li> {@link MotorOutputConfigs#DutyCycleNeutralDeadband} 398 * <li> {@link MotorOutputConfigs#PeakForwardDutyCycle} 399 * <li> {@link MotorOutputConfigs#PeakReverseDutyCycle} 400 * <li> {@link MotorOutputConfigs#ControlTimesyncFreqHz} 401 * </ul> 402 * 403 * 404 * @param newMotorOutput Parameter to modify 405 * @return Itself 406 */ 407 public TalonFXConfiguration withMotorOutput(MotorOutputConfigs newMotorOutput) 408 { 409 MotorOutput = newMotorOutput; 410 return this; 411 } 412 413 /** 414 * Modifies this configuration's CurrentLimits parameter and returns itself for 415 * method-chaining and easier to use config API. 416 * <p> 417 * Configs that directly affect current limiting features. 418 * <p> 419 * Contains the supply/stator current limit thresholds and whether to 420 * enable them. 421 * <p> 422 * Parameter list: 423 * 424 * <ul> 425 * <li> {@link CurrentLimitsConfigs#StatorCurrentLimit} 426 * <li> {@link CurrentLimitsConfigs#StatorCurrentLimitEnable} 427 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLimit} 428 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLimitEnable} 429 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLowerLimit} 430 * <li> {@link CurrentLimitsConfigs#SupplyCurrentLowerTime} 431 * </ul> 432 * 433 * 434 * @param newCurrentLimits Parameter to modify 435 * @return Itself 436 */ 437 public TalonFXConfiguration withCurrentLimits(CurrentLimitsConfigs newCurrentLimits) 438 { 439 CurrentLimits = newCurrentLimits; 440 return this; 441 } 442 443 /** 444 * Modifies this configuration's Voltage parameter and returns itself for 445 * method-chaining and easier to use config API. 446 * <p> 447 * Configs that affect Voltage control types. 448 * <p> 449 * Includes peak output voltages and other configs affecting voltage 450 * measurements. 451 * <p> 452 * Parameter list: 453 * 454 * <ul> 455 * <li> {@link VoltageConfigs#SupplyVoltageTimeConstant} 456 * <li> {@link VoltageConfigs#PeakForwardVoltage} 457 * <li> {@link VoltageConfigs#PeakReverseVoltage} 458 * </ul> 459 * 460 * 461 * @param newVoltage Parameter to modify 462 * @return Itself 463 */ 464 public TalonFXConfiguration withVoltage(VoltageConfigs newVoltage) 465 { 466 Voltage = newVoltage; 467 return this; 468 } 469 470 /** 471 * Modifies this configuration's TorqueCurrent parameter and returns itself for 472 * method-chaining and easier to use config API. 473 * <p> 474 * Configs that affect Torque Current control types. 475 * <p> 476 * Includes the maximum and minimum applied torque output and the 477 * neutral deadband used during TorqueCurrentFOC requests. 478 * <p> 479 * Parameter list: 480 * 481 * <ul> 482 * <li> {@link TorqueCurrentConfigs#PeakForwardTorqueCurrent} 483 * <li> {@link TorqueCurrentConfigs#PeakReverseTorqueCurrent} 484 * <li> {@link TorqueCurrentConfigs#TorqueNeutralDeadband} 485 * </ul> 486 * 487 * 488 * @param newTorqueCurrent Parameter to modify 489 * @return Itself 490 */ 491 public TalonFXConfiguration withTorqueCurrent(TorqueCurrentConfigs newTorqueCurrent) 492 { 493 TorqueCurrent = newTorqueCurrent; 494 return this; 495 } 496 497 /** 498 * Modifies this configuration's Feedback parameter and returns itself for 499 * method-chaining and easier to use config API. 500 * <p> 501 * Configs that affect the feedback of this motor controller. 502 * <p> 503 * Includes feedback sensor source, any offsets for the feedback 504 * sensor, and various ratios to describe the relationship between the 505 * sensor and the mechanism for closed looping. 506 * <p> 507 * Parameter list: 508 * 509 * <ul> 510 * <li> {@link FeedbackConfigs#FeedbackRotorOffset} 511 * <li> {@link FeedbackConfigs#SensorToMechanismRatio} 512 * <li> {@link FeedbackConfigs#RotorToSensorRatio} 513 * <li> {@link FeedbackConfigs#FeedbackSensorSource} 514 * <li> {@link FeedbackConfigs#FeedbackRemoteSensorID} 515 * <li> {@link FeedbackConfigs#VelocityFilterTimeConstant} 516 * </ul> 517 * 518 * 519 * @param newFeedback Parameter to modify 520 * @return Itself 521 */ 522 public TalonFXConfiguration withFeedback(FeedbackConfigs newFeedback) 523 { 524 Feedback = newFeedback; 525 return this; 526 } 527 528 /** 529 * Modifies this configuration's DifferentialSensors parameter and returns itself for 530 * method-chaining and easier to use config API. 531 * <p> 532 * Configs related to sensors used for differential control of a 533 * mechanism. 534 * <p> 535 * Includes the differential sensor sources and IDs. 536 * <p> 537 * Parameter list: 538 * 539 * <ul> 540 * <li> {@link DifferentialSensorsConfigs#DifferentialSensorSource} 541 * <li> {@link 542 * DifferentialSensorsConfigs#DifferentialTalonFXSensorID} 543 * <li> {@link 544 * DifferentialSensorsConfigs#DifferentialRemoteSensorID} 545 * </ul> 546 * 547 * 548 * @param newDifferentialSensors Parameter to modify 549 * @return Itself 550 */ 551 public TalonFXConfiguration withDifferentialSensors(DifferentialSensorsConfigs newDifferentialSensors) 552 { 553 DifferentialSensors = newDifferentialSensors; 554 return this; 555 } 556 557 /** 558 * Modifies this configuration's DifferentialConstants parameter and returns itself for 559 * method-chaining and easier to use config API. 560 * <p> 561 * Configs related to constants used for differential control of a 562 * mechanism. 563 * <p> 564 * Includes the differential peak outputs. 565 * <p> 566 * Parameter list: 567 * 568 * <ul> 569 * <li> {@link 570 * DifferentialConstantsConfigs#PeakDifferentialDutyCycle} 571 * <li> {@link DifferentialConstantsConfigs#PeakDifferentialVoltage} 572 * <li> {@link 573 * DifferentialConstantsConfigs#PeakDifferentialTorqueCurrent} 574 * </ul> 575 * 576 * 577 * @param newDifferentialConstants Parameter to modify 578 * @return Itself 579 */ 580 public TalonFXConfiguration withDifferentialConstants(DifferentialConstantsConfigs newDifferentialConstants) 581 { 582 DifferentialConstants = newDifferentialConstants; 583 return this; 584 } 585 586 /** 587 * Modifies this configuration's OpenLoopRamps parameter and returns itself for 588 * method-chaining and easier to use config API. 589 * <p> 590 * Configs that affect the open-loop control of this motor controller. 591 * <p> 592 * Open-loop ramp rates for the various control types. 593 * <p> 594 * Parameter list: 595 * 596 * <ul> 597 * <li> {@link OpenLoopRampsConfigs#DutyCycleOpenLoopRampPeriod} 598 * <li> {@link OpenLoopRampsConfigs#VoltageOpenLoopRampPeriod} 599 * <li> {@link OpenLoopRampsConfigs#TorqueOpenLoopRampPeriod} 600 * </ul> 601 * 602 * 603 * @param newOpenLoopRamps Parameter to modify 604 * @return Itself 605 */ 606 public TalonFXConfiguration withOpenLoopRamps(OpenLoopRampsConfigs newOpenLoopRamps) 607 { 608 OpenLoopRamps = newOpenLoopRamps; 609 return this; 610 } 611 612 /** 613 * Modifies this configuration's ClosedLoopRamps parameter and returns itself for 614 * method-chaining and easier to use config API. 615 * <p> 616 * Configs that affect the closed-loop control of this motor 617 * controller. 618 * <p> 619 * Closed-loop ramp rates for the various control types. 620 * <p> 621 * Parameter list: 622 * 623 * <ul> 624 * <li> {@link ClosedLoopRampsConfigs#DutyCycleClosedLoopRampPeriod} 625 * <li> {@link ClosedLoopRampsConfigs#VoltageClosedLoopRampPeriod} 626 * <li> {@link ClosedLoopRampsConfigs#TorqueClosedLoopRampPeriod} 627 * </ul> 628 * 629 * 630 * @param newClosedLoopRamps Parameter to modify 631 * @return Itself 632 */ 633 public TalonFXConfiguration withClosedLoopRamps(ClosedLoopRampsConfigs newClosedLoopRamps) 634 { 635 ClosedLoopRamps = newClosedLoopRamps; 636 return this; 637 } 638 639 /** 640 * Modifies this configuration's HardwareLimitSwitch parameter and returns itself for 641 * method-chaining and easier to use config API. 642 * <p> 643 * Configs that change how the motor controller behaves under 644 * different limit switch states. 645 * <p> 646 * Includes configs such as enabling limit switches, configuring the 647 * remote sensor ID, the source, and the position to set on limit. 648 * <p> 649 * Parameter list: 650 * 651 * <ul> 652 * <li> {@link HardwareLimitSwitchConfigs#ForwardLimitType} 653 * <li> {@link 654 * HardwareLimitSwitchConfigs#ForwardLimitAutosetPositionEnable} 655 * <li> {@link 656 * HardwareLimitSwitchConfigs#ForwardLimitAutosetPositionValue} 657 * <li> {@link HardwareLimitSwitchConfigs#ForwardLimitEnable} 658 * <li> {@link HardwareLimitSwitchConfigs#ForwardLimitSource} 659 * <li> {@link 660 * HardwareLimitSwitchConfigs#ForwardLimitRemoteSensorID} 661 * <li> {@link HardwareLimitSwitchConfigs#ReverseLimitType} 662 * <li> {@link 663 * HardwareLimitSwitchConfigs#ReverseLimitAutosetPositionEnable} 664 * <li> {@link 665 * HardwareLimitSwitchConfigs#ReverseLimitAutosetPositionValue} 666 * <li> {@link HardwareLimitSwitchConfigs#ReverseLimitEnable} 667 * <li> {@link HardwareLimitSwitchConfigs#ReverseLimitSource} 668 * <li> {@link 669 * HardwareLimitSwitchConfigs#ReverseLimitRemoteSensorID} 670 * </ul> 671 * 672 * 673 * @param newHardwareLimitSwitch Parameter to modify 674 * @return Itself 675 */ 676 public TalonFXConfiguration withHardwareLimitSwitch(HardwareLimitSwitchConfigs newHardwareLimitSwitch) 677 { 678 HardwareLimitSwitch = newHardwareLimitSwitch; 679 return this; 680 } 681 682 /** 683 * Modifies this configuration's Audio parameter and returns itself for 684 * method-chaining and easier to use config API. 685 * <p> 686 * Configs that affect audible components of the device. 687 * <p> 688 * Includes configuration for the beep on boot. 689 * <p> 690 * Parameter list: 691 * 692 * <ul> 693 * <li> {@link AudioConfigs#BeepOnBoot} 694 * <li> {@link AudioConfigs#BeepOnConfig} 695 * <li> {@link AudioConfigs#AllowMusicDurDisable} 696 * </ul> 697 * 698 * 699 * @param newAudio Parameter to modify 700 * @return Itself 701 */ 702 public TalonFXConfiguration withAudio(AudioConfigs newAudio) 703 { 704 Audio = newAudio; 705 return this; 706 } 707 708 /** 709 * Modifies this configuration's SoftwareLimitSwitch parameter and returns itself for 710 * method-chaining and easier to use config API. 711 * <p> 712 * Configs that affect how software-limit switches behave. 713 * <p> 714 * Includes enabling software-limit switches and the threshold at 715 * which they are tripped. 716 * <p> 717 * Parameter list: 718 * 719 * <ul> 720 * <li> {@link SoftwareLimitSwitchConfigs#ForwardSoftLimitEnable} 721 * <li> {@link SoftwareLimitSwitchConfigs#ReverseSoftLimitEnable} 722 * <li> {@link SoftwareLimitSwitchConfigs#ForwardSoftLimitThreshold} 723 * <li> {@link SoftwareLimitSwitchConfigs#ReverseSoftLimitThreshold} 724 * </ul> 725 * 726 * 727 * @param newSoftwareLimitSwitch Parameter to modify 728 * @return Itself 729 */ 730 public TalonFXConfiguration withSoftwareLimitSwitch(SoftwareLimitSwitchConfigs newSoftwareLimitSwitch) 731 { 732 SoftwareLimitSwitch = newSoftwareLimitSwitch; 733 return this; 734 } 735 736 /** 737 * Modifies this configuration's MotionMagic parameter and returns itself for 738 * method-chaining and easier to use config API. 739 * <p> 740 * Configs for Motion MagicĀ®. 741 * <p> 742 * Includes Velocity, Acceleration, Jerk, and Expo parameters. 743 * <p> 744 * Parameter list: 745 * 746 * <ul> 747 * <li> {@link MotionMagicConfigs#MotionMagicCruiseVelocity} 748 * <li> {@link MotionMagicConfigs#MotionMagicAcceleration} 749 * <li> {@link MotionMagicConfigs#MotionMagicJerk} 750 * <li> {@link MotionMagicConfigs#MotionMagicExpo_kV} 751 * <li> {@link MotionMagicConfigs#MotionMagicExpo_kA} 752 * </ul> 753 * 754 * 755 * @param newMotionMagic Parameter to modify 756 * @return Itself 757 */ 758 public TalonFXConfiguration withMotionMagic(MotionMagicConfigs newMotionMagic) 759 { 760 MotionMagic = newMotionMagic; 761 return this; 762 } 763 764 /** 765 * Modifies this configuration's CustomParams parameter and returns itself for 766 * method-chaining and easier to use config API. 767 * <p> 768 * Custom Params. 769 * <p> 770 * Custom paramaters that have no real impact on controller. 771 * <p> 772 * Parameter list: 773 * 774 * <ul> 775 * <li> {@link CustomParamsConfigs#CustomParam0} 776 * <li> {@link CustomParamsConfigs#CustomParam1} 777 * </ul> 778 * 779 * 780 * @param newCustomParams Parameter to modify 781 * @return Itself 782 */ 783 public TalonFXConfiguration withCustomParams(CustomParamsConfigs newCustomParams) 784 { 785 CustomParams = newCustomParams; 786 return this; 787 } 788 789 /** 790 * Modifies this configuration's ClosedLoopGeneral parameter and returns itself for 791 * method-chaining and easier to use config API. 792 * <p> 793 * Configs that affect general behavior during closed-looping. 794 * <p> 795 * Includes Continuous Wrap features. 796 * <p> 797 * Parameter list: 798 * 799 * <ul> 800 * <li> {@link ClosedLoopGeneralConfigs#ContinuousWrap} 801 * </ul> 802 * 803 * 804 * @param newClosedLoopGeneral Parameter to modify 805 * @return Itself 806 */ 807 public TalonFXConfiguration withClosedLoopGeneral(ClosedLoopGeneralConfigs newClosedLoopGeneral) 808 { 809 ClosedLoopGeneral = newClosedLoopGeneral; 810 return this; 811 } 812 813 /** 814 * Modifies this configuration's Slot0 parameter and returns itself for 815 * method-chaining and easier to use config API. 816 * <p> 817 * Gains for the specified slot. 818 * <p> 819 * If this slot is selected, these gains are used in closed loop 820 * control requests. 821 * <p> 822 * Parameter list: 823 * 824 * <ul> 825 * <li> {@link Slot0Configs#kP} 826 * <li> {@link Slot0Configs#kI} 827 * <li> {@link Slot0Configs#kD} 828 * <li> {@link Slot0Configs#kS} 829 * <li> {@link Slot0Configs#kV} 830 * <li> {@link Slot0Configs#kA} 831 * <li> {@link Slot0Configs#kG} 832 * <li> {@link Slot0Configs#GravityType} 833 * <li> {@link Slot0Configs#StaticFeedforwardSign} 834 * </ul> 835 * 836 * 837 * @param newSlot0 Parameter to modify 838 * @return Itself 839 */ 840 public TalonFXConfiguration withSlot0(Slot0Configs newSlot0) 841 { 842 Slot0 = newSlot0; 843 return this; 844 } 845 846 /** 847 * Modifies this configuration's Slot1 parameter and returns itself for 848 * method-chaining and easier to use config API. 849 * <p> 850 * Gains for the specified slot. 851 * <p> 852 * If this slot is selected, these gains are used in closed loop 853 * control requests. 854 * <p> 855 * Parameter list: 856 * 857 * <ul> 858 * <li> {@link Slot1Configs#kP} 859 * <li> {@link Slot1Configs#kI} 860 * <li> {@link Slot1Configs#kD} 861 * <li> {@link Slot1Configs#kS} 862 * <li> {@link Slot1Configs#kV} 863 * <li> {@link Slot1Configs#kA} 864 * <li> {@link Slot1Configs#kG} 865 * <li> {@link Slot1Configs#GravityType} 866 * <li> {@link Slot1Configs#StaticFeedforwardSign} 867 * </ul> 868 * 869 * 870 * @param newSlot1 Parameter to modify 871 * @return Itself 872 */ 873 public TalonFXConfiguration withSlot1(Slot1Configs newSlot1) 874 { 875 Slot1 = newSlot1; 876 return this; 877 } 878 879 /** 880 * Modifies this configuration's Slot2 parameter and returns itself for 881 * method-chaining and easier to use config API. 882 * <p> 883 * Gains for the specified slot. 884 * <p> 885 * If this slot is selected, these gains are used in closed loop 886 * control requests. 887 * <p> 888 * Parameter list: 889 * 890 * <ul> 891 * <li> {@link Slot2Configs#kP} 892 * <li> {@link Slot2Configs#kI} 893 * <li> {@link Slot2Configs#kD} 894 * <li> {@link Slot2Configs#kS} 895 * <li> {@link Slot2Configs#kV} 896 * <li> {@link Slot2Configs#kA} 897 * <li> {@link Slot2Configs#kG} 898 * <li> {@link Slot2Configs#GravityType} 899 * <li> {@link Slot2Configs#StaticFeedforwardSign} 900 * </ul> 901 * 902 * 903 * @param newSlot2 Parameter to modify 904 * @return Itself 905 */ 906 public TalonFXConfiguration withSlot2(Slot2Configs newSlot2) 907 { 908 Slot2 = newSlot2; 909 return this; 910 } 911 912 @Override 913 public String toString() 914 { 915 String ss = "TalonFXConfiguration\n"; 916 ss += MotorOutput.toString(); 917 ss += CurrentLimits.toString(); 918 ss += Voltage.toString(); 919 ss += TorqueCurrent.toString(); 920 ss += Feedback.toString(); 921 ss += DifferentialSensors.toString(); 922 ss += DifferentialConstants.toString(); 923 ss += OpenLoopRamps.toString(); 924 ss += ClosedLoopRamps.toString(); 925 ss += HardwareLimitSwitch.toString(); 926 ss += Audio.toString(); 927 ss += SoftwareLimitSwitch.toString(); 928 ss += MotionMagic.toString(); 929 ss += CustomParams.toString(); 930 ss += ClosedLoopGeneral.toString(); 931 ss += Slot0.toString(); 932 ss += Slot1.toString(); 933 ss += Slot2.toString(); 934 return ss; 935 } 936 937 /** 938 * Get the serialized form of this configuration 939 * 940 * @return Serialized form of this config group 941 */ 942 public String serialize() 943 { 944 String ss = ""; 945 ss += MotorOutput.serialize(); 946 ss += CurrentLimits.serialize(); 947 ss += Voltage.serialize(); 948 ss += TorqueCurrent.serialize(); 949 ss += Feedback.serialize(); 950 ss += DifferentialSensors.serialize(); 951 ss += DifferentialConstants.serialize(); 952 ss += OpenLoopRamps.serialize(); 953 ss += ClosedLoopRamps.serialize(); 954 ss += HardwareLimitSwitch.serialize(); 955 ss += Audio.serialize(); 956 ss += SoftwareLimitSwitch.serialize(); 957 ss += MotionMagic.serialize(); 958 ss += CustomParams.serialize(); 959 ss += ClosedLoopGeneral.serialize(); 960 ss += Slot0.serialize(); 961 ss += Slot1.serialize(); 962 ss += Slot2.serialize(); 963 return ss; 964 } 965 966 /** 967 * Take a string and deserialize it to this configuration 968 * 969 * @return Return code of the deserialize method 970 */ 971 public StatusCode deserialize(String to_deserialize) 972 { 973 StatusCode err = StatusCode.OK; 974 err = MotorOutput.deserialize(to_deserialize); 975 err = CurrentLimits.deserialize(to_deserialize); 976 err = Voltage.deserialize(to_deserialize); 977 err = TorqueCurrent.deserialize(to_deserialize); 978 err = Feedback.deserialize(to_deserialize); 979 err = DifferentialSensors.deserialize(to_deserialize); 980 err = DifferentialConstants.deserialize(to_deserialize); 981 err = OpenLoopRamps.deserialize(to_deserialize); 982 err = ClosedLoopRamps.deserialize(to_deserialize); 983 err = HardwareLimitSwitch.deserialize(to_deserialize); 984 err = Audio.deserialize(to_deserialize); 985 err = SoftwareLimitSwitch.deserialize(to_deserialize); 986 err = MotionMagic.deserialize(to_deserialize); 987 err = CustomParams.deserialize(to_deserialize); 988 err = ClosedLoopGeneral.deserialize(to_deserialize); 989 err = Slot0.deserialize(to_deserialize); 990 err = Slot1.deserialize(to_deserialize); 991 err = Slot2.deserialize(to_deserialize); 992 return err; 993 } 994};