001/* 002 * Copyright (c) 2018-2022 REV Robotics 003 * 004 * Redistribution and use in source and binary forms, with or without 005 * modification, are permitted provided that the following conditions are met: 006 * 007 * 1. Redistributions of source code must retain the above copyright notice, 008 * this list of conditions and the following disclaimer. 009 * 2. Redistributions in binary form must reproduce the above copyright 010 * notice, this list of conditions and the following disclaimer in the 011 * documentation and/or other materials provided with the distribution. 012 * 3. Neither the name of REV Robotics nor the names of its 013 * contributors may be used to endorse or promote products derived from 014 * this software without specific prior written permission. 015 * 016 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 017 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 018 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 019 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 020 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 021 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 022 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 023 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 024 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 025 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 026 * POSSIBILITY OF SUCH DAMAGE. 027 */ 028 029package com.revrobotics; 030 031import com.revrobotics.jni.CANSparkMaxJNI; 032 033public class CANSparkMax extends CANSparkMaxLowLevel { 034 public enum IdleMode { 035 kCoast(0), 036 kBrake(1); 037 038 @SuppressWarnings("MemberName") 039 public final int value; 040 041 IdleMode(int value) { 042 this.value = value; 043 } 044 045 public static IdleMode fromId(int id) { 046 if (id == 1) { 047 return kBrake; 048 } 049 return kCoast; 050 } 051 } 052 053 @Deprecated(forRemoval = true) 054 public enum InputMode { 055 kPWM(0), 056 kCAN(1); 057 058 @SuppressWarnings("MemberName") 059 public final int value; 060 061 InputMode(int value) { 062 this.value = value; 063 } 064 065 public static InputMode fromId(int id) { 066 if (id == 1) { 067 return kCAN; 068 } 069 return kPWM; 070 } 071 } 072 073 public enum SoftLimitDirection { 074 kForward(0), 075 kReverse(1); 076 077 @SuppressWarnings("MemberName") 078 public final int value; 079 080 SoftLimitDirection(int value) { 081 this.value = value; 082 } 083 084 public static SoftLimitDirection fromID(int id) { 085 if (id == 1) { 086 return kReverse; 087 } 088 return kForward; 089 } 090 } 091 092 public enum FaultID { 093 kBrownout(0), 094 kOvercurrent(1), 095 kIWDTReset(2), 096 kMotorFault(3), 097 kSensorFault(4), 098 kStall(5), 099 kEEPROMCRC(6), 100 kCANTX(7), 101 kCANRX(8), 102 kHasReset(9), 103 kDRVFault(10), 104 kOtherFault(11), 105 kSoftLimitFwd(12), 106 kSoftLimitRev(13), 107 kHardLimitFwd(14), 108 kHardLimitRev(15); 109 110 @SuppressWarnings("MemberName") 111 public final int value; 112 113 FaultID(int value) { 114 this.value = value; 115 } 116 117 public static FaultID fromId(int id) { 118 for (FaultID type : values()) { 119 if (type.value == id) { 120 return type; 121 } 122 } 123 return null; 124 } 125 } 126 127 public enum ControlType { 128 kDutyCycle(0), 129 kVelocity(1), 130 kVoltage(2), 131 kPosition(3), 132 kSmartMotion(4), 133 kCurrent(5), 134 kSmartVelocity(6); 135 136 @SuppressWarnings("MemberName") 137 public final int value; 138 139 ControlType(int value) { 140 this.value = value; 141 } 142 } 143 144 public static class ExternalFollower { 145 private final int arbId; 146 private final int configId; 147 148 public static final ExternalFollower kFollowerDisabled = new ExternalFollower(0, 0); 149 public static final ExternalFollower kFollowerSparkMax = new ExternalFollower(0x2051800, 26); 150 public static final ExternalFollower kFollowerPhoenix = new ExternalFollower(0x2040080, 27); 151 152 public ExternalFollower(int arbId, int configId) { 153 this.arbId = arbId; 154 this.configId = configId; 155 } 156 } 157 158 private SparkMaxRelativeEncoder encoder; 159 private final Object encoderLock = new Object(); 160 161 private SparkMaxAlternateEncoder altEncoder; 162 private final Object altEncoderLock = new Object(); 163 164 private SparkMaxAnalogSensor analogSensor; 165 private final Object analogSensorLock = new Object(); 166 167 private SparkMaxPIDController pidController; 168 private final Object pidControllerLock = new Object(); 169 170 private SparkMaxLimitSwitch forwardLimitSwitch; 171 private final Object forwardLimitSwitchLock = new Object(); 172 173 private SparkMaxLimitSwitch reverseLimitSwitch; 174 private final Object reverseLimitSwitchLock = new Object(); 175 176 // Only used for get() and set() API 177 private double m_setpoint = 0.0; 178 179 /** 180 * Create a new object to control a SPARK MAX motor Controller 181 * 182 * @param deviceId The device ID. 183 * @param type The motor type connected to the controller. Brushless motor wires must be connected 184 * to their matching colors and the hall sensor must be plugged in. Brushed motors must be 185 * connected to the Red and Black terminals only. 186 */ 187 public CANSparkMax(int deviceId, MotorType type) { 188 super(deviceId, type); 189 } 190 191 /** ** Speed Controller Interface *** */ 192 /** 193 * Common interface for setting the speed of a speed controller. 194 * 195 * @param speed The speed to set. Value should be between -1.0 and 1.0. 196 */ 197 @Override 198 public void set(double speed) { 199 throwIfClosed(); 200 // Only for 'get' API 201 m_setpoint = speed; 202 setpointCommand(speed, ControlType.kDutyCycle); 203 } 204 205 /** 206 * Sets the voltage output of the SpeedController. This is equivillant to a call to 207 * SetReference(output, rev::ControlType::kVoltage). The behavior of this call differs slightly 208 * from the WPILib documetation for this call since the device internally sets the desired voltage 209 * (not a compensation value). That means that this *can* be a 'set-and-forget' call. 210 * 211 * @param outputVolts The voltage to output. 212 */ 213 @Override 214 public void setVoltage(double outputVolts) { 215 throwIfClosed(); 216 setpointCommand(outputVolts, ControlType.kVoltage); 217 } 218 219 /** 220 * Common interface for getting the current set speed of a speed controller. 221 * 222 * @return The current set speed. Value is between -1.0 and 1.0. 223 */ 224 @Override 225 public double get() { 226 throwIfClosed(); 227 return m_setpoint; 228 } 229 230 /** 231 * Common interface for inverting direction of a speed controller. 232 * 233 * <p>This call has no effect if the controller is a follower. To invert a follower, see the 234 * follow() method. 235 * 236 * @param isInverted The state of inversion, true is inverted. 237 */ 238 @Override 239 public void setInverted(boolean isInverted) { 240 throwIfClosed(); 241 CANSparkMaxJNI.c_SparkMax_SetInverted(sparkMaxHandle, isInverted); 242 } 243 244 /** 245 * Common interface for returning the inversion state of a speed controller. 246 * 247 * <p>This call has no effect if the controller is a follower. 248 * 249 * @return isInverted The state of inversion, true is inverted. 250 */ 251 @Override 252 public boolean getInverted() { 253 throwIfClosed(); 254 return CANSparkMaxJNI.c_SparkMax_GetInverted(sparkMaxHandle); 255 } 256 257 /** Common interface for disabling a motor. */ 258 @Override 259 public void disable() { 260 throwIfClosed(); 261 set(0); 262 } 263 264 @Override 265 public void stopMotor() { 266 throwIfClosed(); 267 set(0); 268 } 269 270 /** ***** Extended Functions ****** */ 271 /** 272 * Returns an object for interfacing with the hall sensor integrated into a brushless motor, which 273 * is connected to the front port of the SPARK MAX. 274 * 275 * <p>To access a quadrature encoder connected to the encoder pins or the front port of the SPARK 276 * MAX, you must call the version of this method with EncoderType and countsPerRev parameters. 277 * 278 * @return An object for interfacing with the integrated encoder. 279 */ 280 public RelativeEncoder getEncoder() { 281 throwIfClosed(); 282 return getEncoder(SparkMaxRelativeEncoder.Type.kHallSensor, 42); 283 } 284 285 /** 286 * Returns an object for interfacing with the encoder connected to the encoder pins or front port 287 * of the SPARK MAX. 288 * 289 * @param encoderType The encoder type for the motor: kHallEffect or kQuadrature 290 * @param countsPerRev The counts per revolution of the encoder 291 * @return An object for interfacing with an encoder 292 */ 293 public RelativeEncoder getEncoder(SparkMaxRelativeEncoder.Type encoderType, int countsPerRev) { 294 throwIfClosed(); 295 synchronized (encoderLock) { 296 if (encoder == null) { 297 encoder = new SparkMaxRelativeEncoder(this, encoderType, countsPerRev); 298 } else { 299 if (encoder.type != encoderType) { 300 throw new IllegalStateException( 301 "The main encoder on this SPARK MAX has already been initialized as a " 302 + encoder.type); 303 } 304 // Counts per revolution is ignored for the hall sensor encoder type 305 if (encoder.type != SparkMaxRelativeEncoder.Type.kHallSensor 306 && encoder.getCountsPerRevolution() != countsPerRev) { 307 throw new IllegalStateException( 308 "The main encoder on this SPARK MAX has already been initialized with countsPerRev set to " 309 + encoder.countsPerRev); 310 } 311 // The user isn't trying to change their encoder settings mid-program, so we're all set 312 } 313 return encoder; 314 } 315 } 316 317 /** 318 * Returns an object for interfacing with the encoder connected to the encoder pins or front port 319 * of the SPARK MAX. 320 * 321 * @param encoderType The encoder type for the motor: kHallEffect or kQuadrature 322 * @param countsPerRev The counts per revolution of the encoder 323 * @return An object for interfacing with an encoder 324 * @deprecated Use {@link #getEncoder(SparkMaxRelativeEncoder.Type, int)} instead. 325 */ 326 @SuppressWarnings("removal") 327 @Deprecated(forRemoval = true) 328 public RelativeEncoder getEncoder(com.revrobotics.EncoderType encoderType, int countsPerRev) { 329 SparkMaxRelativeEncoder.Type adaptedType = SparkMaxRelativeEncoder.Type.kNoSensor; 330 if (encoderType == com.revrobotics.EncoderType.kHallSensor) { 331 adaptedType = SparkMaxRelativeEncoder.Type.kHallSensor; 332 } else if (encoderType == com.revrobotics.EncoderType.kQuadrature) { 333 adaptedType = SparkMaxRelativeEncoder.Type.kQuadrature; 334 } 335 return getEncoder(adaptedType, countsPerRev); 336 } 337 338 /** 339 * Returns an object for interfacing with a quadrature encoder connected to the alternate encoder 340 * mode data port pins. These are defined as: 341 * 342 * <ul> 343 * <li>Pin 4 (Forward Limit Switch): Index 344 * <li>Pin 6 (Multi-function): Encoder A 345 * <li>Pin 8 (Reverse Limit Switch): Encoder B 346 * </ul> 347 * 348 * <p>This call will disable support for the limit switch inputs. 349 * 350 * @param countsPerRev The counts per revolution of the encoder 351 * @return An object for interfacing with a quadrature encoder connected to the alternate encoder 352 * mode data port pins 353 */ 354 public RelativeEncoder getAlternateEncoder(int countsPerRev) { 355 throwIfClosed(); 356 return getAlternateEncoder(SparkMaxAlternateEncoder.Type.kQuadrature, countsPerRev); 357 } 358 359 /** 360 * Returns an object for interfacing with a quadrature encoder connected to the alternate encoder 361 * mode data port pins. These are defined as: 362 * 363 * <ul> 364 * <li>Pin 4 (Forward Limit Switch): Index 365 * <li>Pin 6 (Multi-function): Encoder A 366 * <li>Pin 8 (Reverse Limit Switch): Encoder B 367 * </ul> 368 * 369 * <p>This call will disable support for the limit switch inputs. 370 * 371 * @param encoderType The encoder type for the motor: currently only kQuadrature 372 * @param countsPerRev The counts per revolution of the encoder 373 * @return An object for interfacing with a quadrature encoder connected to the alternate encoder 374 * mode data port pins 375 */ 376 public RelativeEncoder getAlternateEncoder( 377 SparkMaxAlternateEncoder.Type encoderType, int countsPerRev) { 378 throwIfClosed(); 379 synchronized (altEncoderLock) { 380 if (altEncoder == null) { 381 altEncoder = new SparkMaxAlternateEncoder(this, encoderType, countsPerRev); 382 } else { 383 if (altEncoder.type != encoderType) { 384 throw new IllegalStateException( 385 "The alternate encoder on this SPARK MAX has already been initialized as a " 386 + altEncoder.type); 387 } 388 if (altEncoder.countsPerRev != countsPerRev) { 389 throw new IllegalStateException( 390 "The alternate encoder on this SPARK MAX has already been initialized with countsPerRev set to " 391 + altEncoder.countsPerRev); 392 } 393 // The user isn't trying to change their alternate encoder settings mid-program, 394 // so we're all set 395 } 396 return altEncoder; 397 } 398 } 399 400 /** 401 * Returns an object for interfacing with a quadrature encoder connected to the alternate encoder 402 * mode data port pins. These are defined as: 403 * 404 * <ul> 405 * <li>Pin 4 (Forward Limit Switch): Index 406 * <li>Pin 6 (Multi-function): Encoder A 407 * <li>Pin 8 (Reverse Limit Switch): Encoder B 408 * </ul> 409 * 410 * <p>This call will disable support for the limit switch inputs. 411 * 412 * @param encoderType The encoder type for the motor: currently only kQuadrature 413 * @param countsPerRev The counts per revolution of the encoder 414 * @return An object for interfacing with a quadrature encoder connected to the alternate encoder 415 * mode data port pins 416 */ 417 @SuppressWarnings("removal") 418 @Deprecated(forRemoval = true) 419 public RelativeEncoder getAlternateEncoder( 420 com.revrobotics.AlternateEncoderType encoderType, int countsPerRev) { 421 return getAlternateEncoder(SparkMaxAlternateEncoder.Type.kQuadrature, countsPerRev); 422 } 423 424 /** 425 * @param mode The mode of the analog sensor, either absolute or relative 426 * @return An object for interfacing with a connected analog sensor. 427 */ 428 public SparkMaxAnalogSensor getAnalog(SparkMaxAnalogSensor.Mode mode) { 429 throwIfClosed(); 430 synchronized (analogSensorLock) { 431 if (analogSensor == null) { 432 analogSensor = new SparkMaxAnalogSensor(this, mode); 433 } else { 434 if (analogSensor.mode != mode) { 435 throw new IllegalStateException( 436 "The analog sensor connected to this SPARK MAX has already been configured with mode " 437 + analogSensor.mode); 438 } 439 // The user isn't trying to change their analog sensor settings mid-program, 440 // so we're all set 441 } 442 return analogSensor; 443 } 444 } 445 446 /** @deprecated Use {@link #getAnalog(SparkMaxAnalogSensor.Mode)} instead */ 447 @SuppressWarnings("removal") 448 @Deprecated(forRemoval = true) 449 public SparkMaxAnalogSensor getAnalog(CANAnalog.AnalogMode mode) { 450 SparkMaxAnalogSensor.Mode newMode; 451 if (mode == CANAnalog.AnalogMode.kRelative) { 452 newMode = SparkMaxAnalogSensor.Mode.kRelative; 453 } else { 454 newMode = SparkMaxAnalogSensor.Mode.kAbsolute; 455 } 456 return getAnalog(newMode); 457 } 458 459 /** @return An object for interfacing with the integrated PID controller. */ 460 public SparkMaxPIDController getPIDController() { 461 throwIfClosed(); 462 synchronized (pidControllerLock) { 463 if (pidController == null) { 464 pidController = new SparkMaxPIDController(this); 465 } 466 return pidController; 467 } 468 } 469 470 /** 471 * Returns an object for interfacing with the forward limit switch connected to the appropriate 472 * pins on the data port. 473 * 474 * <p>This call will disable support for the alternate encoder. 475 * 476 * @param polarity Whether the limit switch is normally open or normally closed. 477 * @return An object for interfacing with the forward limit switch. 478 * @deprecated Use {@link #getForwardLimitSwitch(SparkMaxLimitSwitch.Type)} instead. 479 */ 480 @SuppressWarnings("removal") 481 @Deprecated(forRemoval = true) 482 public CANDigitalInput getForwardLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity) { 483 SparkMaxLimitSwitch.Type newType; 484 if (polarity == CANDigitalInput.LimitSwitchPolarity.kNormallyClosed) { 485 newType = SparkMaxLimitSwitch.Type.kNormallyClosed; 486 } else { 487 newType = SparkMaxLimitSwitch.Type.kNormallyOpen; 488 } 489 490 return getForwardLimitSwitch(newType); 491 } 492 493 /** 494 * Returns an object for interfacing with the forward limit switch connected to the appropriate 495 * pins on the data port. 496 * 497 * <p>This call will disable support for the alternate encoder. 498 * 499 * @param switchType Whether the limit switch is normally open or normally closed. 500 * @return An object for interfacing with the forward limit switch. 501 */ 502 public SparkMaxLimitSwitch getForwardLimitSwitch(SparkMaxLimitSwitch.Type switchType) { 503 throwIfClosed(); 504 synchronized (forwardLimitSwitchLock) { 505 if (forwardLimitSwitch == null) { 506 forwardLimitSwitch = 507 new SparkMaxLimitSwitch(this, SparkMaxLimitSwitch.Direction.kForward, switchType); 508 } else { 509 if (forwardLimitSwitch.m_switchType != switchType) { 510 throw new IllegalStateException( 511 "The forward limit switch on this SPARK MAX has already been configured with the" 512 + forwardLimitSwitch.m_switchType 513 + " switch type"); 514 } 515 } 516 return forwardLimitSwitch; 517 } 518 } 519 520 /** 521 * Returns an object for interfacing with the reverse limit switch connected to the appropriate 522 * pins on the data port. 523 * 524 * <p>This call will disable support for the alternate encoder. 525 * 526 * @param polarity Whether the limit switch is normally open or normally closed. 527 * @return An object for interfacing with the reverse limit switch. 528 * @deprecated Use {@link #getReverseLimitSwitch(SparkMaxLimitSwitch.Type)} instead. 529 */ 530 @SuppressWarnings("removal") 531 @Deprecated(forRemoval = true) 532 public CANDigitalInput getReverseLimitSwitch(CANDigitalInput.LimitSwitchPolarity polarity) { 533 SparkMaxLimitSwitch.Type newType; 534 if (polarity == CANDigitalInput.LimitSwitchPolarity.kNormallyClosed) { 535 newType = SparkMaxLimitSwitch.Type.kNormallyClosed; 536 } else { 537 newType = SparkMaxLimitSwitch.Type.kNormallyOpen; 538 } 539 540 return getReverseLimitSwitch(newType); 541 } 542 543 /** 544 * Returns an object for interfacing with the reverse limit switch connected to the appropriate 545 * pins on the data port. 546 * 547 * <p>This call will disable support for the alternate encoder. 548 * 549 * @param switchType Whether the limit switch is normally open or normally closed. 550 * @return An object for interfacing with the reverse limit switch. 551 */ 552 public SparkMaxLimitSwitch getReverseLimitSwitch(SparkMaxLimitSwitch.Type switchType) { 553 throwIfClosed(); 554 synchronized (reverseLimitSwitchLock) { 555 if (reverseLimitSwitch == null) { 556 reverseLimitSwitch = 557 new SparkMaxLimitSwitch(this, SparkMaxLimitSwitch.Direction.kReverse, switchType); 558 } else { 559 if (reverseLimitSwitch.m_switchType != switchType) { 560 throw new IllegalStateException( 561 "The reverse limit switch on this SPARK MAX has already been configured with the " 562 + reverseLimitSwitch.m_switchType 563 + " switch type"); 564 } 565 } 566 return reverseLimitSwitch; 567 } 568 } 569 570 /** 571 * Sets the current limit in Amps. 572 * 573 * <p>The motor controller will reduce the controller voltage output to avoid surpassing this 574 * limit. This limit is enabled by default and used for brushless only. This limit is highly 575 * recommended when using the NEO brushless motor. 576 * 577 * <p>The NEO Brushless Motor has a low internal resistance, which can mean large current spikes 578 * that could be enough to cause damage to the motor and controller. This current limit provides a 579 * smarter strategy to deal with high current draws and keep the motor and controller operating in 580 * a safe region. 581 * 582 * @param limit The current limit in Amps. 583 * @return {@link REVLibError#kOk} if successful 584 */ 585 public REVLibError setSmartCurrentLimit(int limit) { 586 throwIfClosed(); 587 return setSmartCurrentLimit(limit, 0, 20000); 588 } 589 590 /** 591 * Sets the current limit in Amps. 592 * 593 * <p>The motor controller will reduce the controller voltage output to avoid surpassing this 594 * limit. This limit is enabled by default and used for brushless only. This limit is highly 595 * recommended when using the NEO brushless motor. 596 * 597 * <p>The NEO Brushless Motor has a low internal resistance, which can mean large current spikes 598 * that could be enough to cause damage to the motor and controller. This current limit provides a 599 * smarter strategy to deal with high current draws and keep the motor and controller operating in 600 * a safe region. 601 * 602 * <p>The controller can also limit the current based on the RPM of the motor in a linear fashion 603 * to help with controllability in closed loop control. For a response that is linear the entire 604 * RPM range leave limit RPM at 0. 605 * 606 * @param stallLimit The current limit in Amps at 0 RPM. 607 * @param freeLimit The current limit at free speed (5700RPM for NEO). 608 * @return {@link REVLibError#kOk} if successful 609 */ 610 public REVLibError setSmartCurrentLimit(int stallLimit, int freeLimit) { 611 throwIfClosed(); 612 return setSmartCurrentLimit(stallLimit, freeLimit, 20000); 613 } 614 615 /** 616 * Sets the current limit in Amps. 617 * 618 * <p>The motor controller will reduce the controller voltage output to avoid surpassing this 619 * limit. This limit is enabled by default and used for brushless only. This limit is highly 620 * recommended when using the NEO brushless motor. 621 * 622 * <p>The NEO Brushless Motor has a low internal resistance, which can mean large current spikes 623 * that could be enough to cause damage to the motor and controller. This current limit provides a 624 * smarter strategy to deal with high current draws and keep the motor and controller operating in 625 * a safe region. 626 * 627 * <p>The controller can also limit the current based on the RPM of the motor in a linear fashion 628 * to help with controllability in closed loop control. For a response that is linear the entire 629 * RPM range leave limit RPM at 0. 630 * 631 * @param stallLimit The current limit in Amps at 0 RPM. 632 * @param freeLimit The current limit at free speed (5700RPM for NEO). 633 * @param limitRPM RPM less than this value will be set to the stallLimit, RPM values greater than 634 * limitRPM will scale linearly to freeLimit 635 * @return {@link REVLibError#kOk} if successful 636 */ 637 public REVLibError setSmartCurrentLimit(int stallLimit, int freeLimit, int limitRPM) { 638 throwIfClosed(); 639 return REVLibError.fromInt( 640 CANSparkMaxJNI.c_SparkMax_SetSmartCurrentLimit( 641 sparkMaxHandle, stallLimit, freeLimit, limitRPM)); 642 } 643 644 /** 645 * Sets the secondary current limit in Amps. 646 * 647 * <p>The motor controller will disable the output of the controller briefly if the current limit 648 * is exceeded to reduce the current. This limit is a simplified 'on/off' controller. This limit 649 * is enabled by default but is set higher than the default Smart Current Limit. 650 * 651 * <p>The time the controller is off after the current limit is reached is determined by the 652 * parameter limitCycles, which is the number of PWM cycles (20kHz). The recommended value is the 653 * default of 0 which is the minimum time and is part of a PWM cycle from when the over current is 654 * detected. This allows the controller to regulate the current close to the limit value. 655 * 656 * <p>The total time is set by the equation <code> 657 * t = (50us - t0) + 50us * limitCycles 658 * t = total off time after over current 659 * t0 = time from the start of the PWM cycle until over current is detected 660 * </code> 661 * 662 * @param limit The current limit in Amps. 663 * @return {@link REVLibError#kOk} if successful 664 */ 665 public REVLibError setSecondaryCurrentLimit(double limit) { 666 throwIfClosed(); 667 return setSecondaryCurrentLimit(limit, 0); 668 } 669 670 /** 671 * Sets the secondary current limit in Amps. 672 * 673 * <p>The motor controller will disable the output of the controller briefly if the current limit 674 * is exceeded to reduce the current. This limit is a simplified 'on/off' controller. This limit 675 * is enabled by default but is set higher than the default Smart Current Limit. 676 * 677 * <p>The time the controller is off after the current limit is reached is determined by the 678 * parameter limitCycles, which is the number of PWM cycles (20kHz). The recommended value is the 679 * default of 0 which is the minimum time and is part of a PWM cycle from when the over current is 680 * detected. This allows the controller to regulate the current close to the limit value. 681 * 682 * <p>The total time is set by the equation <code> 683 * t = (50us - t0) + 50us * limitCycles 684 * t = total off time after over current 685 * t0 = time from the start of the PWM cycle until over current is detected 686 * </code> 687 * 688 * @param limit The current limit in Amps. 689 * @param chopCycles The number of additional PWM cycles to turn the driver off after overcurrent 690 * is detected. 691 * @return {@link REVLibError#kOk} if successful 692 */ 693 public REVLibError setSecondaryCurrentLimit(double limit, int chopCycles) { 694 throwIfClosed(); 695 return REVLibError.fromInt( 696 CANSparkMaxJNI.c_SparkMax_SetSecondaryCurrentLimit( 697 sparkMaxHandle, (float) limit, chopCycles)); 698 } 699 700 /** 701 * Sets the idle mode setting for the SPARK MAX. 702 * 703 * @param mode Idle mode (coast or brake). 704 * @return {@link REVLibError#kOk} if successful 705 */ 706 public REVLibError setIdleMode(IdleMode mode) { 707 throwIfClosed(); 708 return REVLibError.fromInt(CANSparkMaxJNI.c_SparkMax_SetIdleMode(sparkMaxHandle, mode.value)); 709 } 710 711 /** 712 * Gets the idle mode setting for the SPARK MAX. 713 * 714 * <p>This uses the Get Parameter API and should be used infrequently. This function uses a 715 * non-blocking call and will return a cached value if the parameter is not returned by the 716 * timeout. The timeout can be changed by calling SetCANTimeout(int milliseconds) 717 * 718 * @return IdleMode Idle mode setting 719 */ 720 public IdleMode getIdleMode() { 721 throwIfClosed(); 722 return IdleMode.fromId(CANSparkMaxJNI.c_SparkMax_GetIdleMode(sparkMaxHandle)); 723 } 724 725 /** 726 * Sets the voltage compensation setting for all modes on the SPARK MAX and enables voltage 727 * compensation. 728 * 729 * @param nominalVoltage Nominal voltage to compensate output to 730 * @return {@link REVLibError#kOk} if successful 731 */ 732 public REVLibError enableVoltageCompensation(double nominalVoltage) { 733 throwIfClosed(); 734 return REVLibError.fromInt( 735 CANSparkMaxJNI.c_SparkMax_EnableVoltageCompensation( 736 sparkMaxHandle, (float) nominalVoltage)); 737 } 738 739 /** 740 * Disables the voltage compensation setting for all modes on the SPARK MAX. 741 * 742 * @return {@link REVLibError#kOk} if successful 743 */ 744 public REVLibError disableVoltageCompensation() { 745 throwIfClosed(); 746 return REVLibError.fromInt( 747 CANSparkMaxJNI.c_SparkMax_DisableVoltageCompensation(sparkMaxHandle)); 748 } 749 750 /** 751 * Get the configured voltage compensation nominal voltage value 752 * 753 * @return The nominal voltage for voltage compensation mode. 754 */ 755 public double getVoltageCompensationNominalVoltage() { 756 throwIfClosed(); 757 return (double) CANSparkMaxJNI.c_SparkMax_GetVoltageCompensationNominalVoltage(sparkMaxHandle); 758 } 759 760 /** 761 * Sets the ramp rate for open loop control modes. 762 * 763 * <p>This is the maximum rate at which the motor controller's output is allowed to change. 764 * 765 * @param rate Time in seconds to go from 0 to full throttle. 766 * @return {@link REVLibError#kOk} if successful 767 */ 768 public REVLibError setOpenLoopRampRate(double rate) { 769 throwIfClosed(); 770 return REVLibError.fromInt( 771 CANSparkMaxJNI.c_SparkMax_SetOpenLoopRampRate(sparkMaxHandle, (float) rate)); 772 } 773 774 /** 775 * Sets the ramp rate for closed loop control modes. 776 * 777 * <p>This is the maximum rate at which the motor controller's output is allowed to change. 778 * 779 * @param rate Time in seconds to go from 0 to full throttle. 780 * @return {@link REVLibError#kOk} if successful 781 */ 782 public REVLibError setClosedLoopRampRate(double rate) { 783 throwIfClosed(); 784 return REVLibError.fromInt( 785 CANSparkMaxJNI.c_SparkMax_SetClosedLoopRampRate(sparkMaxHandle, (float) rate)); 786 } 787 788 /** 789 * Get the configured open loop ramp rate 790 * 791 * <p>This is the maximum rate at which the motor controller's output is allowed to change. 792 * 793 * @return ramp rate time in seconds to go from 0 to full throttle. 794 */ 795 public double getOpenLoopRampRate() { 796 throwIfClosed(); 797 return (double) CANSparkMaxJNI.c_SparkMax_GetOpenLoopRampRate(sparkMaxHandle); 798 } 799 800 /** 801 * Get the configured closed loop ramp rate 802 * 803 * <p>This is the maximum rate at which the motor controller's output is allowed to change. 804 * 805 * @return ramp rate time in seconds to go from 0 to full throttle. 806 */ 807 public double getClosedLoopRampRate() { 808 throwIfClosed(); 809 return (double) CANSparkMaxJNI.c_SparkMax_GetClosedLoopRampRate(sparkMaxHandle); 810 } 811 812 /** 813 * Causes this controller's output to mirror the provided leader. 814 * 815 * <p>Only voltage output is mirrored. Settings changed on the leader do not affect the follower. 816 * 817 * <p>The motor will spin in the same direction as the leader. This can be changed by passing a 818 * true constant after the leader parameter. 819 * 820 * <p>Following anything other than a CAN SPARK MAX is not officially supported. 821 * 822 * @param leader The motor controller to follow. 823 * @return {@link REVLibError#kOk} if successful 824 */ 825 public REVLibError follow(final CANSparkMax leader) { 826 throwIfClosed(); 827 return follow(leader, false); 828 } 829 830 /** 831 * Causes this controller's output to mirror the provided leader. 832 * 833 * <p>Only voltage output is mirrored. Settings changed on the leader do not affect the follower. 834 * 835 * <p>Following anything other than a CAN SPARK MAX is not officially supported. 836 * 837 * @param leader The motor controller to follow. 838 * @param invert Set the follower to output opposite of the leader 839 * @return {@link REVLibError#kOk} if successful 840 */ 841 public REVLibError follow(final CANSparkMax leader, boolean invert) { 842 throwIfClosed(); 843 return follow(ExternalFollower.kFollowerSparkMax, leader.getDeviceId(), invert); 844 } 845 846 /** 847 * Causes this controller's output to mirror the provided leader. 848 * 849 * <p>Only voltage output is mirrored. Settings changed on the leader do not affect the follower. 850 * 851 * <p>The motor will spin in the same direction as the leader. This can be changed by passing a 852 * true constant after the deviceID parameter. 853 * 854 * <p>Following anything other than a CAN SPARK MAX is not officially supported. 855 * 856 * @param leader The type of motor controller to follow (Talon SRX, SPARK MAX, etc.). 857 * @param deviceID The CAN ID of the device to follow. 858 * @return {@link REVLibError#kOk} if successful 859 */ 860 public REVLibError follow(ExternalFollower leader, int deviceID) { 861 throwIfClosed(); 862 boolean inverted = CANSparkMaxJNI.c_SparkMax_GetInverted(sparkMaxHandle); 863 return follow(leader, deviceID, inverted); 864 } 865 866 /** 867 * Causes this controller's output to mirror the provided leader. 868 * 869 * <p>Only voltage output is mirrored. Settings changed on the leader do not affect the follower. 870 * 871 * <p>Following anything other than a CAN SPARK MAX is not officially supported. 872 * 873 * @param leader The type of motor controller to follow (Talon SRX, SPARK MAX, etc.). 874 * @param deviceID The CAN ID of the device to follow. 875 * @param invert Set the follower to output opposite of the leader 876 * @return {@link REVLibError#kOk} if successful 877 */ 878 public REVLibError follow(ExternalFollower leader, int deviceID, boolean invert) { 879 throwIfClosed(); 880 FollowConfig maxFollower = new FollowConfig(); 881 maxFollower.leaderArbId = (leader.arbId == 0 ? 0 : leader.arbId | deviceID); 882 maxFollower.config.predefined = leader.configId; 883 maxFollower.config.invert = invert ? 1 : 0; 884 return setFollow(maxFollower); 885 } 886 887 /** 888 * Returns whether the controller is following another controller 889 * 890 * @return True if this device is following another controller false otherwise 891 */ 892 public boolean isFollower() { 893 throwIfClosed(); 894 return CANSparkMaxJNI.c_SparkMax_IsFollower(sparkMaxHandle); 895 } 896 897 /** @return All fault bits as a short */ 898 public short getFaults() { 899 throwIfClosed(); 900 return (short) CANSparkMaxJNI.c_SparkMax_GetFaults(sparkMaxHandle); 901 } 902 903 /** @return All sticky fault bits as a short */ 904 public short getStickyFaults() { 905 throwIfClosed(); 906 return (short) CANSparkMaxJNI.c_SparkMax_GetStickyFaults(sparkMaxHandle); 907 } 908 909 /** 910 * Get the value of a specific fault 911 * 912 * @param faultID The ID of the fault to retrive 913 * @return True if the fault with the given ID occurred. 914 */ 915 public boolean getFault(FaultID faultID) { 916 throwIfClosed(); 917 return CANSparkMaxJNI.c_SparkMax_GetFault(sparkMaxHandle, faultID.value); 918 } 919 920 /** 921 * Get the value of a specific sticky fault 922 * 923 * @param faultID The ID of the sticky fault to retrive 924 * @return True if the sticky fault with the given ID occurred. 925 */ 926 public boolean getStickyFault(FaultID faultID) { 927 throwIfClosed(); 928 return CANSparkMaxJNI.c_SparkMax_GetStickyFault(sparkMaxHandle, faultID.value); 929 } 930 931 /** @return The voltage fed into the motor controller. */ 932 public double getBusVoltage() { 933 throwIfClosed(); 934 return (double) CANSparkMaxJNI.c_SparkMax_GetBusVoltage(sparkMaxHandle); 935 } 936 937 /** @return The motor controller's applied output duty cycle. */ 938 public double getAppliedOutput() { 939 throwIfClosed(); 940 return (double) CANSparkMaxJNI.c_SparkMax_GetAppliedOutput(sparkMaxHandle); 941 } 942 943 /** @return The motor controller's output current in Amps. */ 944 public double getOutputCurrent() { 945 throwIfClosed(); 946 return (double) CANSparkMaxJNI.c_SparkMax_GetOutputCurrent(sparkMaxHandle); 947 } 948 949 /** @return The motor temperature in Celsius. */ 950 public double getMotorTemperature() { 951 throwIfClosed(); 952 return (double) CANSparkMaxJNI.c_SparkMax_GetMotorTemperature(sparkMaxHandle); 953 } 954 955 /** 956 * Clears all sticky faults. 957 * 958 * @return {@link REVLibError#kOk} if successful 959 */ 960 public REVLibError clearFaults() { 961 throwIfClosed(); 962 return REVLibError.fromInt(CANSparkMaxJNI.c_SparkMax_ClearFaults(sparkMaxHandle)); 963 } 964 965 /** 966 * Writes all settings to flash. 967 * 968 * @return {@link REVLibError#kOk} if successful 969 */ 970 public REVLibError burnFlash() { 971 throwIfClosed(); 972 return REVLibError.fromInt(CANSparkMaxJNI.c_SparkMax_BurnFlash(sparkMaxHandle)); 973 } 974 975 /** 976 * Sets timeout for sending CAN messages with SetParameter* and GetParameter* calls. These calls 977 * will block for up to this amoutn of time before returning a timeout erro. A timeout of 0 will 978 * make the SetParameter* calls non-blocking, and instead will check the response in a separate 979 * thread. With this configuration, any error messages will appear on the drivestration but will 980 * not be returned by the GetLastError() call. 981 * 982 * @param milliseconds The timeout in milliseconds. 983 * @return {@link REVLibError#kOk} if successful 984 */ 985 public REVLibError setCANTimeout(int milliseconds) { 986 throwIfClosed(); 987 return REVLibError.fromInt( 988 CANSparkMaxJNI.c_SparkMax_SetCANTimeout(sparkMaxHandle, milliseconds)); 989 } 990 991 /** 992 * Enable soft limits 993 * 994 * @param direction the direction of motion to restrict 995 * @param enable set true to enable soft limits 996 * @return {@link REVLibError#kOk} if successful 997 */ 998 public REVLibError enableSoftLimit(SoftLimitDirection direction, boolean enable) { 999 throwIfClosed(); 1000 return REVLibError.fromInt( 1001 CANSparkMaxJNI.c_SparkMax_EnableSoftLimit(sparkMaxHandle, direction.value, enable)); 1002 } 1003 1004 /** 1005 * Set the soft limit based on position. The default unit is rotations, but will match the unit 1006 * scaling set by the user. 1007 * 1008 * <p>Note that this value is not scaled internally so care must be taken to make sure these units 1009 * match the desired conversion 1010 * 1011 * @param direction the direction of motion to restrict 1012 * @param limit position soft limit of the controller 1013 * @return {@link REVLibError#kOk} if successful 1014 */ 1015 public REVLibError setSoftLimit(SoftLimitDirection direction, float limit) { 1016 throwIfClosed(); 1017 return REVLibError.fromInt( 1018 CANSparkMaxJNI.c_SparkMax_SetSoftLimit(sparkMaxHandle, direction.value, limit)); 1019 } 1020 1021 /** 1022 * Get the soft limit setting in the controller 1023 * 1024 * @param direction the direction of motion to restrict 1025 * @return position soft limit setting of the controller 1026 */ 1027 public double getSoftLimit(SoftLimitDirection direction) { 1028 throwIfClosed(); 1029 return (double) CANSparkMaxJNI.c_SparkMax_GetSoftLimit(sparkMaxHandle, direction.value); 1030 } 1031 1032 /** 1033 * @param direction The direction of the motion to restrict 1034 * @return true if the soft limit is enabled. 1035 */ 1036 public boolean isSoftLimitEnabled(SoftLimitDirection direction) { 1037 throwIfClosed(); 1038 return (boolean) CANSparkMaxJNI.c_SparkMax_IsSoftLimitEnabled(sparkMaxHandle, direction.value); 1039 } 1040 1041 /** 1042 * Gets the feedback device ID that was set on SparkMax itself. 1043 * 1044 * @return Feedback device ID on the SparkMax 1045 */ 1046 protected int getFeedbackDeviceID() { 1047 throwIfClosed(); 1048 return (int) CANSparkMaxJNI.c_SparkMax_GetFeedbackDeviceID(sparkMaxHandle); 1049 } 1050 1051 /** 1052 * All device errors are tracked on a per thread basis for all devices in that thread. This is 1053 * meant to be called immediately following another call that has the possibility of returning an 1054 * error to validate if an error has occurred. 1055 * 1056 * @return the last error that was generated. 1057 */ 1058 public REVLibError getLastError() { 1059 throwIfClosed(); 1060 return REVLibError.fromInt(CANSparkMaxJNI.c_SparkMax_GetLastError(sparkMaxHandle)); 1061 } 1062 1063 /** 1064 * Set the free speed of the motor being simulated. 1065 * 1066 * @param freeSpeed the free speed (RPM) of the motor connected to spark max 1067 * @return {@link REVLibError#kOk} if successful 1068 */ 1069 REVLibError setSimFreeSpeed(float freeSpeed) { 1070 throwIfClosed(); 1071 return REVLibError.fromInt( 1072 CANSparkMaxJNI.c_SparkMax_SetSimFreeSpeed(sparkMaxHandle, freeSpeed)); 1073 } 1074 1075 /** 1076 * Set the stall torque of the motor being simulated. 1077 * 1078 * @param stallTorque The stall torque (N m) of the motor connected to sparkmax 1079 * @return {@link REVLibError#kOk} if successful 1080 */ 1081 REVLibError setSimStallTorque(float stallTorque) { 1082 throwIfClosed(); 1083 return REVLibError.fromInt( 1084 CANSparkMaxJNI.c_SparkMax_SetSimStallTorque(sparkMaxHandle, stallTorque)); 1085 } 1086 1087 // package-private 1088 enum DataPortConfig { 1089 kNone(-1, "none"), 1090 kLimitSwitches(0, "limit switches"), 1091 kAltEncoder(1, "alternate encoder"); 1092 1093 final int m_value; 1094 final String m_name; 1095 1096 DataPortConfig(int value, String name) { 1097 m_value = value; 1098 m_name = name; 1099 } 1100 1101 public static DataPortConfig fromInt(int id) { 1102 for (DataPortConfig type : values()) { 1103 if (type.m_value == id) { 1104 return type; 1105 } 1106 } 1107 return kNone; 1108 } 1109 } 1110}