001/* Copyright (C) Cross The Road Electronics 2024 */ 002/* 003 * Software License Agreement 004 * 005 * Copyright (C) Cross The Road Electronics. All rights 006 * reserved. 007 * 008 * Cross The Road Electronics (CTRE) licenses to you the right to 009 * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software 010 * API Libraries ONLY when in use with Cross The Road Electronics hardware products. 011 * 012 * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT 013 * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT 014 * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A 015 * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL 016 * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL, 017 * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF 018 * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS 019 * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE 020 * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER 021 * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT 022 * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE 023 */ 024 025package com.ctre.phoenix; 026 027import com.ctre.phoenix.CANifierConfiguration; 028import com.ctre.phoenix.VelocityPeriod; 029import com.ctre.phoenix.ErrorCollection; 030import com.ctre.phoenix.ParamEnum; 031import com.ctre.phoenix.sensors.SensorVelocityMeasPeriod; 032 033/** 034 * CTRE CANifier 035 * 036 * Device for interfacing common devices to the CAN bus. 037 */ 038public class CANifier { 039 private long m_handle; 040 041 042 043 /** 044 * Enum for the LED Output Channels 045 */ 046 public enum LEDChannel { 047 /** 048 * LED Channel A 049 */ 050 LEDChannelA(0), 051 /** 052 * LED Channel B 053 */ 054 LEDChannelB(1), 055 /** 056 * LED Channel C 057 */ 058 LEDChannelC(2); 059 060 /** 061 * Get the LED Channel from a specified value 062 * @param value integer value to get LEDChannel from 063 * @return LEDChannel of specified value 064 */ 065 public static LEDChannel valueOf(int value) { 066 for (LEDChannel mode : values()) { 067 if (mode.value == value) { 068 return mode; 069 } 070 } 071 return null; 072 } 073 074 /** 075 * Value of LEDChannel 076 */ 077 public final int value; 078 079 /** 080 * Create LEDChannel from initValue 081 * @param initValue LEDChannel value 082 */ 083 LEDChannel(int initValue) { 084 this.value = initValue; 085 } 086 } 087 088 /** 089 * Enum for the PWM Input Channels 090 */ 091 public enum PWMChannel { 092 /** 093 * PWM Channel 0 094 */ 095 PWMChannel0(0), 096 /** 097 * PWM Channel 1 098 */ 099 PWMChannel1(1), 100 /** 101 * PWM Channel 2 102 */ 103 PWMChannel2(2), 104 /** 105 * PWM Channel 3 106 */ 107 PWMChannel3(3); 108 109 /** 110 * Get the PWM Channel from a specified value 111 * @param value integer value to get pwm channel from 112 * @return PWM Channel of specified value 113 */ 114 public static PWMChannel valueOf(int value) { 115 for (PWMChannel mode : values()) { 116 if (mode.value == value) { 117 return mode; 118 } 119 } 120 return null; 121 } 122 123 /** 124 * Value of PWM Channel 125 */ 126 public final int value; 127 128 /** 129 * Create a PWM Channel of initValue 130 * @param initValue PWM Channel value 131 */ 132 PWMChannel(int initValue) { 133 this.value = initValue; 134 } 135 } 136 137 /** 138 * Number of PWM channels available to CANifier 139 */ 140 public final int PWMChannelCount = 4; 141 142 /** 143 * General IO Pins on the CANifier 144 */ 145 public enum GeneralPin { 146 /** 147 * Quadrature Idx pin 148 */ 149 QUAD_IDX (CANifierJNI.GeneralPin.QUAD_IDX.value), 150 /** 151 * Quadrature B pin 152 */ 153 QUAD_B (CANifierJNI.GeneralPin.QUAD_B.value), 154 /** 155 * Quadrature A pin 156 */ 157 QUAD_A (CANifierJNI.GeneralPin.QUAD_A.value), 158 /** 159 * Reverse limit pin 160 */ 161 LIMR (CANifierJNI.GeneralPin.LIMR.value), 162 /** 163 * Forward limit pin 164 */ 165 LIMF (CANifierJNI.GeneralPin.LIMF.value), 166 /** 167 * SDA pin 168 */ 169 SDA (CANifierJNI.GeneralPin.SDA.value), 170 /** 171 * SCL pin 172 */ 173 SCL (CANifierJNI.GeneralPin.SCL.value), 174 /** 175 * SPI_CS pin 176 */ 177 SPI_CS (CANifierJNI.GeneralPin.SPI_CS.value), 178 /** 179 * SPI_MISO_PWM2 pin 180 */ 181 SPI_MISO_PWM2P (CANifierJNI.GeneralPin.SPI_MISO_PWM2P.value), 182 /** 183 * SPI_MOSI_PWM1 pin 184 */ 185 SPI_MOSI_PWM1P (CANifierJNI.GeneralPin.SPI_MOSI_PWM1P.value), 186 /** 187 * SPI_CLK_PWM0 pin 188 */ 189 SPI_CLK_PWM0P (CANifierJNI.GeneralPin.SPI_CLK_PWM0P.value); 190 191 /** 192 * Gets the GeneralPin of a specified value 193 * @param value integer value of GeneralPin 194 * @return GeneralPin of specified value 195 */ 196 public static GeneralPin valueOf(int value) { 197 for (GeneralPin mode : values()) { 198 if (mode.value == value) { 199 return mode; 200 } 201 } 202 return null; 203 } 204 205 /** 206 * Value of specified pin 207 */ 208 public final int value; 209 210 /** 211 * Create GeneralPin of initValue value 212 * @param initValue Value of Pin 213 */ 214 GeneralPin(int initValue) { 215 this.value = initValue; 216 } 217 } 218 219 /** 220 * Class to hold the pin values. 221 */ 222 public static class PinValues { 223 /** 224 * Quadrature Idx pin 225 */ 226 public boolean QUAD_IDX; 227 /** 228 * Quadrature B pin 229 */ 230 public boolean QUAD_B; 231 /** 232 * Quadrature A pin 233 */ 234 public boolean QUAD_A; 235 /** 236 * Reverse limit pin 237 */ 238 public boolean LIMR; 239 /** 240 * Forward limit pin 241 */ 242 public boolean LIMF; 243 /** 244 * SDA pin 245 */ 246 public boolean SDA; 247 /** 248 * SCL pin 249 */ 250 public boolean SCL; 251 /** 252 * SPI_CS_PWM3 pin 253 */ 254 public boolean SPI_CS_PWM3; 255 /** 256 * SPI_MISO_PWM2 pin 257 */ 258 public boolean SPI_MISO_PWM2; 259 /** 260 * SPI_MOSI_PWM1 pin 261 */ 262 public boolean SPI_MOSI_PWM1; 263 /** 264 * SPI_CLK_PWM0 pin 265 */ 266 public boolean SPI_CLK_PWM0; 267 } 268 269 private boolean[] _tempPins = new boolean[11]; 270 271 private int m_deviceNumber; 272 /** 273 * Constructor. 274 * @param deviceId The CAN Device ID of the CANifier. 275 */ 276 public CANifier(int deviceId) { 277 m_handle = CANifierJNI.JNI_new_CANifier(deviceId); 278 m_deviceNumber = deviceId; 279 } 280 281 /** 282 * Destructor 283 * @return Error Code generated by function. 0 indicates no error. 284 */ 285 public ErrorCode DestroyObject() { 286 return ErrorCode.valueOf(CANifierJNI.JNI_destroy_CANifier(m_handle)); 287 } 288 289 /** 290 * Sets the LED Output 291 * @param percentOutput Output duty cycle expressed as percentage. 292 * @param ledChannel Channel to set the output of. 293 */ 294 public void setLEDOutput(double percentOutput, LEDChannel ledChannel) { 295 /* convert float to integral fixed pt */ 296 if (percentOutput > 1) { 297 percentOutput = 1; 298 } 299 if (percentOutput < 0) { 300 percentOutput = 0; 301 } 302 int dutyCycle = (int) (percentOutput * 1023); // [0,1023] 303 304 CANifierJNI.JNI_SetLEDOutput(m_handle, dutyCycle, ledChannel.value); 305 } 306 307 /** 308 * Sets the output of a General Pin 309 * @param outputPin The pin to use as output. 310 * @param outputValue The desired output state. 311 * @param outputEnable Whether this pin is an output. "True" enables output. 312 */ 313 public void setGeneralOutput(GeneralPin outputPin, boolean outputValue, boolean outputEnable) { 314 CANifierJNI.JNI_SetGeneralOutput(m_handle, outputPin.value, outputValue, outputEnable); 315 } 316 317 /** 318 * Sets the output of all General Pins 319 * @param outputBits A bit mask of all the output states. LSB->MSB is in the order of the com.ctre.phoenix.CANifier.GeneralPin enum. 320 * @param isOutputBits A boolean bit mask that sets the pins to be outputs or inputs. A bit of 1 enables output. 321 */ 322 public void setGeneralOutputs(int outputBits, int isOutputBits) { 323 CANifierJNI.JNI_SetGeneralOutputs(m_handle, outputBits, isOutputBits); 324 } 325 326 /** 327 * Gets the state of all General Pins 328 * @param allPins A structure to fill with the current state of all pins. 329 */ 330 public void getGeneralInputs(PinValues allPins) { 331 CANifierJNI.JNI_GetGeneralInputs(m_handle, _tempPins); 332 allPins.LIMF = _tempPins[GeneralPin.LIMF.value]; 333 allPins.LIMR = _tempPins[GeneralPin.LIMR.value]; 334 allPins.QUAD_A = _tempPins[GeneralPin.QUAD_A.value]; 335 allPins.QUAD_B = _tempPins[GeneralPin.QUAD_B.value]; 336 allPins.QUAD_IDX = _tempPins[GeneralPin.QUAD_IDX.value]; 337 allPins.SCL = _tempPins[GeneralPin.SCL.value]; 338 allPins.SDA = _tempPins[GeneralPin.SDA.value]; 339 allPins.SPI_CLK_PWM0 = _tempPins[GeneralPin.SPI_CLK_PWM0P.value]; 340 allPins.SPI_MOSI_PWM1 = _tempPins[GeneralPin.SPI_MOSI_PWM1P.value]; 341 allPins.SPI_MISO_PWM2 = _tempPins[GeneralPin.SPI_MISO_PWM2P.value]; 342 allPins.SPI_CS_PWM3 = _tempPins[GeneralPin.SPI_CS.value]; 343 } 344 345 /** 346 * Gets the state of the specified pin 347 * @param inputPin The index of the pin. 348 * @return The state of the pin. 349 */ 350 public boolean getGeneralInput(GeneralPin inputPin) { 351 return CANifierJNI.JNI_GetGeneralInput(m_handle, inputPin.value); 352 } 353 354 /** 355 * Call GetLastError() generated by this object. 356 * Not all functions return an error code but can 357 * potentially report errors. 358 * 359 * This function can be used to retrieve those error codes. 360 * 361 * @return The last ErrorCode generated. 362 */ 363 public ErrorCode getLastError() { 364 int retval = CANifierJNI.JNI_GetLastError(m_handle); 365 return ErrorCode.valueOf(retval); 366 } 367 368 /** 369 * Sets the PWM Output 370 * Currently supports PWM 0, PWM 1, and PWM 2 371 * @param pwmChannel Index of the PWM channel to output. 372 * @param dutyCycle Duty Cycle (0 to 1) to output. Default period of the signal is 4.2 ms. 373 */ 374 public void setPWMOutput(int pwmChannel, double dutyCycle) { 375 if (dutyCycle < 0) { 376 dutyCycle = 0; 377 } else if (dutyCycle > 1) { 378 dutyCycle = 1; 379 } 380 if (pwmChannel < 0) { 381 pwmChannel = 0; 382 } 383 384 int dutyCyc10bit = (int) (1023 * dutyCycle); 385 386 CANifierJNI.JNI_SetPWMOutput(m_handle, (int) pwmChannel, dutyCyc10bit); 387 } 388 389 /** 390 * Enables PWM Outputs 391 * Currently supports PWM 0, PWM 1, and PWM 2 392 * @param pwmChannel Index of the PWM channel to enable. 393 * @param bEnable "True" enables output on the pwm channel. 394 */ 395 public void enablePWMOutput(int pwmChannel, boolean bEnable) { 396 if (pwmChannel < 0) { 397 pwmChannel = 0; 398 } 399 400 CANifierJNI.JNI_EnablePWMOutput(m_handle, (int) pwmChannel, bEnable); 401 } 402 403 /** 404 * Gets the PWM Input 405 * @param pwmChannel PWM channel to get. 406 * @param pulseWidthAndPeriod Double array to hold Duty Cycle [0] and Period [1]. 407 */ 408 public void getPWMInput(PWMChannel pwmChannel, double[] pulseWidthAndPeriod) { 409 CANifierJNI.JNI_GetPWMInput(m_handle, pwmChannel.value, pulseWidthAndPeriod); 410 } 411 412 /** 413 * Gets the quadrature encoder's position 414 * @return Position of encoder 415 */ 416 public int getQuadraturePosition() { 417 return CANifierJNI.JNI_GetQuadraturePosition(m_handle); 418 } 419 420 /** 421 * Sets the quadrature encoder's position 422 * @param newPosition Position to set 423 * @param timeoutMs 424 Timeout value in ms. If nonzero, function will wait for 425 config success and report an error if it times out. 426 If zero, no blocking or checking is performed. 427 * @return Error Code generated by function. 0 indicates no error. 428 */ 429 public ErrorCode setQuadraturePosition(int newPosition, int timeoutMs) { 430 return ErrorCode.valueOf(CANifierJNI.JNI_SetQuadraturePosition(m_handle, newPosition, timeoutMs)); 431 } 432 433 /** 434 * Gets the quadrature encoder's velocity 435 * @return Velocity of encoder 436 */ 437 public int getQuadratureVelocity() { 438 return CANifierJNI.JNI_GetQuadratureVelocity(m_handle); 439 } 440 441 /** 442 * Configures the period of each velocity sample. 443 * Every 1ms a position value is sampled, and the delta between that sample 444 * and the position sampled kPeriod ms ago is inserted into a filter. 445 * kPeriod is configured with this function. 446 * 447 * @param period 448 * Desired period for the velocity measurement. @see 449 * com.ctre.phoenix.sensors.SensorVelocityMeasPeriod 450 * @param timeoutMs 451 * Timeout value in ms. If nonzero, function will wait for 452 * config success and report an error if it times out. 453 * If zero, no blocking or checking is performed. 454 * @return Error Code generated by function. 0 indicates no error. 455 */ 456 public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs) { 457 int retval = CANifierJNI.JNI_ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs); 458 return ErrorCode.valueOf(retval); 459 } 460 461 /** 462 * Configures the period of each velocity sample. 463 * Every 1ms a position value is sampled, and the delta between that sample 464 * and the position sampled kPeriod ms ago is inserted into a filter. 465 * kPeriod is configured with this function. 466 * 467 * @deprecated Use the overload with SensorVelocityMeasPeriod instead. 468 * 469 * @param period 470 * Desired period for the velocity measurement. @see 471 * com.ctre.phoenix.VelocityMeasPeriod 472 * @param timeoutMs 473 * Timeout value in ms. If nonzero, function will wait for 474 * config success and report an error if it times out. 475 * If zero, no blocking or checking is performed. 476 * @return Error Code generated by function. 0 indicates no error. 477 */ 478 @Deprecated 479 public ErrorCode configVelocityMeasurementPeriod(VelocityPeriod period, int timeoutMs) { 480 int retval = CANifierJNI.JNI_ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs); 481 return ErrorCode.valueOf(retval); 482 } 483 /** 484 * Configures the period of each velocity sample. 485 * Every 1ms a position value is sampled, and the delta between that sample 486 * and the position sampled kPeriod ms ago is inserted into a filter. 487 * kPeriod is configured with this function. 488 * 489 * @param period 490 * Desired period for the velocity measurement. @see 491 * com.ctre.phoenix.sensor.SensorVelocityMeasPeriod 492 * @return Error Code generated by function. 0 indicates no error. 493 */ 494 public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period) { 495 int timeoutMs = 0; 496 return configVelocityMeasurementPeriod(period, timeoutMs); 497 } 498 /** 499 * Configures the period of each velocity sample. 500 * Every 1ms a position value is sampled, and the delta between that sample 501 * and the position sampled kPeriod ms ago is inserted into a filter. 502 * kPeriod is configured with this function. 503 * 504 * @deprecated Use the overload with SensorVelocityMeasPeriod instead. 505 * 506 * @param period 507 * Desired period for the velocity measurement. @see 508 * com.ctre.phoenix.motorcontrol.VelocityMeasPeriod 509 * @return Error Code generated by function. 0 indicates no error. 510 */ 511 @Deprecated 512 public ErrorCode configVelocityMeasurementPeriod(VelocityPeriod period) { 513 int timeoutMs = 0; 514 return configVelocityMeasurementPeriod(period, timeoutMs); 515 } 516 517 /** 518 * Sets the number of velocity samples used in the rolling average velocity 519 * measurement. 520 * 521 * @param windowSize 522 * Number of samples in the rolling average of velocity 523 * measurement. Valid values are 1,2,4,8,16,32. If another 524 * value is specified, it will truncate to nearest support value. 525 * @param timeoutMs 526 * Timeout value in ms. If nonzero, function will wait for 527 * config success and report an error if it times out. 528 * If zero, no blocking or checking is performed. 529 * @return Error Code generated by function. 0 indicates no error. 530 */ 531 public ErrorCode configVelocityMeasurementWindow(int windowSize, int timeoutMs) { 532 int retval = CANifierJNI.JNI_ConfigVelocityMeasurementWindow(m_handle, windowSize, timeoutMs); 533 return ErrorCode.valueOf(retval); 534 } 535 /** 536 * Sets the number of velocity samples used in the rolling average velocity 537 * measurement. 538 * 539 * @param windowSize 540 * Number of samples in the rolling average of velocity 541 * measurement. Valid values are 1,2,4,8,16,32. If another 542 * value is specified, it will truncate to nearest support value. 543 * @return Error Code generated by function. 0 indicates no error. 544 */ 545 public ErrorCode configVelocityMeasurementWindow(int windowSize) { 546 int timeoutMs = 0; 547 return configVelocityMeasurementWindow( windowSize, timeoutMs); 548 } 549 550 /** 551 * Enables clearing the position of the feedback sensor when the forward 552 * limit switch is triggered 553 * 554 * @param clearPositionOnLimitF Whether clearing is enabled, defaults false 555 * @param timeoutMs 556 * Timeout value in ms. If nonzero, function will wait for 557 * config success and report an error if it times out. 558 * If zero, no blocking or checking is performed. 559 * @return Error Code generated by function. 0 indicates no error. 560 */ 561 public ErrorCode configClearPositionOnLimitF(boolean clearPositionOnLimitF, int timeoutMs) { 562 int retval = CANifierJNI.JNI_ConfigClearPositionOnLimitF(m_handle, clearPositionOnLimitF, timeoutMs); 563 return ErrorCode.valueOf(retval); 564 } 565 /** 566 * Enables clearing the position of the feedback sensor when the reverse 567 * limit switch is triggered 568 * 569 * @param clearPositionOnLimitR Whether clearing is enabled, defaults false 570 * @param timeoutMs 571 * Timeout value in ms. If nonzero, function will wait for 572 * config success and report an error if it times out. 573 * If zero, no blocking or checking is performed. 574 * @return Error Code generated by function. 0 indicates no error. 575 */ 576 public ErrorCode configClearPositionOnLimitR(boolean clearPositionOnLimitR, int timeoutMs) { 577 int retval = CANifierJNI.JNI_ConfigClearPositionOnLimitR(m_handle, clearPositionOnLimitR, timeoutMs); 578 return ErrorCode.valueOf(retval); 579 } 580 /** 581 * Enables clearing the position of the feedback sensor when the quadrature index signal 582 * is detected 583 * 584 * @param clearPositionOnQuadIdx Whether clearing is enabled, defaults false 585 * @param timeoutMs 586 * Timeout value in ms. If nonzero, function will wait for 587 * config success and report an error if it times out. 588 * If zero, no blocking or checking is performed. 589 * @return Error Code generated by function. 0 indicates no error. 590 */ 591 public ErrorCode configClearPositionOnQuadIdx(boolean clearPositionOnQuadIdx, int timeoutMs) { 592 int retval = CANifierJNI.JNI_ConfigClearPositionOnQuadIdx(m_handle, clearPositionOnQuadIdx, timeoutMs); 593 return ErrorCode.valueOf(retval); 594 } 595 /** 596 * Sets the value of a custom parameter. This is for arbitrary use. 597 * 598 * Sometimes it is necessary to save calibration/duty cycle/output 599 * information in the device. Particularly if the 600 * device is part of a subsystem that can be replaced. 601 * 602 * @param newValue 603 * Value for custom parameter. 604 * @param paramIndex 605 * Index of custom parameter. [0-1] 606 * @param timeoutMs 607 * Timeout value in ms. If nonzero, function will wait for 608 * config success and report an error if it times out. 609 * If zero, no blocking or checking is performed. 610 * @return Error Code generated by function. 0 indicates no error. 611 */ 612 public ErrorCode configSetCustomParam(int newValue, int paramIndex, int timeoutMs) { 613 int retval = CANifierJNI.JNI_ConfigSetCustomParam(m_handle, newValue, paramIndex, timeoutMs); 614 return ErrorCode.valueOf(retval); 615 } 616 /** 617 * Sets the value of a custom parameter. This is for arbitrary use. 618 * 619 * Sometimes it is necessary to save calibration/duty cycle/output 620 * information in the device. Particularly if the 621 * device is part of a subsystem that can be replaced. 622 * 623 * @param newValue 624 * Value for custom parameter. 625 * @param paramIndex 626 * Index of custom parameter. [0-1] 627 * @return Error Code generated by function. 0 indicates no error. 628 */ 629 public ErrorCode configSetCustomParam(int newValue, int paramIndex) { 630 631 int timeoutMs = 0; 632 return configSetCustomParam( newValue, paramIndex, timeoutMs); 633 } 634 635 /** 636 * Gets the value of a custom parameter. This is for arbitrary use. 637 * 638 * Sometimes it is necessary to save calibration/duty cycle/output 639 * information in the device. Particularly if the 640 * device is part of a subsystem that can be replaced. 641 * 642 * @param paramIndex 643 * Index of custom parameter. [0-1] 644 * @param timeoutMs 645 * Timeout value in ms. If nonzero, function will wait for 646 * config success and report an error if it times out. 647 * If zero, no blocking or checking is performed. 648 * @return Value of the custom param. 649 */ 650 public int configGetCustomParam(int paramIndex, int timeoutMs) { 651 int retval = CANifierJNI.JNI_ConfigGetCustomParam(m_handle, paramIndex, timeoutMs); 652 return retval; 653 } 654 /** 655 * Gets the value of a custom parameter. This is for arbitrary use. 656 * 657 * Sometimes it is necessary to save calibration/duty cycle/output 658 * information in the device. Particularly if the 659 * device is part of a subsystem that can be replaced. 660 * 661 * @param paramIndex 662 * Index of custom parameter. [0-1] 663 * @return Value of the custom param. 664 */ 665 public int configGetCustomParam(int paramIndex) { 666 int timeoutMs = 0; 667 return configGetCustomParam( paramIndex, timeoutMs); 668 } 669 670 /** 671 * Sets a parameter. Generally this is not used. 672 * This can be utilized in 673 * - Using new features without updating API installation. 674 * - Errata workarounds to circumvent API implementation. 675 * - Allows for rapid testing / unit testing of firmware. 676 * 677 * @param param 678 * Parameter enumeration. 679 * @param value 680 * Value of parameter. 681 * @param subValue 682 * Subvalue for parameter. Maximum value of 255. 683 * @param ordinal 684 * Ordinal of parameter. 685 * @param timeoutMs 686 * Timeout value in ms. If nonzero, function will wait for 687 * config success and report an error if it times out. 688 * If zero, no blocking or checking is performed. 689 * @return Error Code generated by function. 0 indicates no error. 690 */ 691 public ErrorCode configSetParameter(ParamEnum param, double value, int subValue, int ordinal, int timeoutMs) { 692 return configSetParameter(param.value, value, subValue, ordinal, timeoutMs); 693 } 694 /** 695 * Sets a parameter. Generally this is not used. 696 * This can be utilized in 697 * - Using new features without updating API installation. 698 * - Errata workarounds to circumvent API implementation. 699 * - Allows for rapid testing / unit testing of firmware. 700 * 701 * @param param 702 * Parameter enumeration. 703 * @param value 704 * Value of parameter. 705 * @param subValue 706 * Subvalue for parameter. Maximum value of 255. 707 * @param ordinal 708 * Ordinal of parameter. 709 * @return Error Code generated by function. 0 indicates no error. 710 */ 711 public ErrorCode configSetParameter(ParamEnum param, double value, int subValue, int ordinal) { 712 int timeoutMs = 0; 713 return configSetParameter(param, value, subValue, ordinal, timeoutMs); 714 } 715 716 /** 717 * Sets a parameter. Generally this is not used. 718 * This can be utilized in 719 * - Using new features without updating API installation. 720 * - Errata workarounds to circumvent API implementation. 721 * - Allows for rapid testing / unit testing of firmware. 722 * 723 * @param param 724 * Parameter enumeration. 725 * @param value 726 * Value of parameter. 727 * @param subValue 728 * Subvalue for parameter. Maximum value of 255. 729 * @param ordinal 730 * Ordinal of parameter. 731 * @param timeoutMs 732 * Timeout value in ms. If nonzero, function will wait for 733 * config success and report an error if it times out. 734 * If zero, no blocking or checking is performed. 735 * @return Error Code generated by function. 0 indicates no error. 736 */ 737 public ErrorCode configSetParameter(int param, double value, int subValue, int ordinal, int timeoutMs) { 738 int retval = CANifierJNI.JNI_ConfigSetParameter(m_handle, param, value, subValue, ordinal, 739 timeoutMs); 740 return ErrorCode.valueOf(retval); 741 } 742 /** 743 * Sets a parameter. Generally this is not used. 744 * This can be utilized in 745 * - Using new features without updating API installation. 746 * - Errata workarounds to circumvent API implementation. 747 * - Allows for rapid testing / unit testing of firmware. 748 * 749 * @param param 750 * Parameter enumeration. 751 * @param value 752 * Value of parameter. 753 * @param subValue 754 * Subvalue for parameter. Maximum value of 255. 755 * @param ordinal 756 * Ordinal of parameter. 757 * @return Error Code generated by function. 0 indicates no error. 758 */ 759 public ErrorCode configSetParameter(int param, double value, int subValue, int ordinal) { 760 int timeoutMs = 0; 761 return configSetParameter( param, value, subValue, ordinal, timeoutMs); 762 } 763 /** 764 * Gets a parameter. Generally this is not used. 765 * This can be utilized in 766 * - Using new features without updating API installation. 767 * - Errata workarounds to circumvent API implementation. 768 * - Allows for rapid testing / unit testing of firmware. 769 * 770 * @param param 771 * Parameter enumeration. 772 * @param ordinal 773 * Ordinal of parameter. 774 * @param timeoutMs 775 * Timeout value in ms. If nonzero, function will wait for 776 * config success and report an error if it times out. 777 * If zero, no blocking or checking is performed. 778 * @return Value of parameter. 779 */ 780 public double configGetParameter(ParamEnum param, int ordinal, int timeoutMs) { 781 return CANifierJNI.JNI_ConfigGetParameter(m_handle, param.value, ordinal, timeoutMs); 782 } 783 /** 784 * Gets a parameter. Generally this is not used. 785 * This can be utilized in 786 * - Using new features without updating API installation. 787 * - Errata workarounds to circumvent API implementation. 788 * - Allows for rapid testing / unit testing of firmware. 789 * 790 * @param param 791 * Parameter enumeration. 792 * @param ordinal 793 * Ordinal of parameter. 794 * @return Value of parameter. 795 */ 796 public double configGetParameter(ParamEnum param, int ordinal) { 797 int timeoutMs = 0; 798 return configGetParameter(param, ordinal, timeoutMs); 799 } 800 /** 801 * Sets the period of the given status frame. 802 * 803 * @param statusFrame 804 * Frame whose period is to be changed. 805 * @param periodMs 806 * Period in ms for the given frame. 807 * @param timeoutMs 808 * Timeout value in ms. If nonzero, function will wait for 809 * config success and report an error if it times out. 810 * If zero, no blocking or checking is performed. 811 * @return Error Code generated by function. 0 indicates no error. 812 */ 813 public ErrorCode setStatusFramePeriod(CANifierStatusFrame statusFrame, int periodMs, int timeoutMs) { 814 int retval = CANifierJNI.JNI_SetStatusFramePeriod(m_handle, statusFrame.value, periodMs, timeoutMs); 815 return ErrorCode.valueOf(retval); 816 } 817 /** 818 * Sets the period of the given status frame. 819 * 820 * @param statusFrame 821 * Frame whose period is to be changed. 822 * @param periodMs 823 * Period in ms for the given frame. 824 * @return Error Code generated by function. 0 indicates no error. 825 */ 826 public ErrorCode setStatusFramePeriod(CANifierStatusFrame statusFrame, int periodMs) { 827 int timeoutMs = 0; 828 return setStatusFramePeriod(statusFrame, periodMs, timeoutMs); 829 } 830 /** 831 * Sets the period of the given status frame. 832 * 833 * @param statusFrame 834 * Frame whose period is to be changed. 835 * @param periodMs 836 * Period in ms for the given frame. 837 * @param timeoutMs 838 * Timeout value in ms. If nonzero, function will wait for 839 * config success and report an error if it times out. 840 * If zero, no blocking or checking is performed. 841 * @return Error Code generated by function. 0 indicates no error. 842 */ 843 public ErrorCode setStatusFramePeriod(int statusFrame, int periodMs, int timeoutMs) { 844 int retval = CANifierJNI.JNI_SetStatusFramePeriod(m_handle, statusFrame, periodMs, timeoutMs); 845 return ErrorCode.valueOf(retval); 846 } 847 /** 848 * Sets the period of the given status frame. 849 * 850 * @param statusFrame 851 * Frame whose period is to be changed. 852 * @param periodMs 853 * Period in ms for the given frame. 854 * @return Error Code generated by function. 0 indicates no error. 855 */ 856 public ErrorCode setStatusFramePeriod(int statusFrame, int periodMs) { 857 int timeoutMs = 0; 858 return setStatusFramePeriod( statusFrame, periodMs, timeoutMs); 859 } 860 861 /** 862 * Gets the period of the given status frame. 863 * 864 * @param frame 865 * Frame to get the period of. 866 * @param timeoutMs 867 * Timeout value in ms. If nonzero, function will wait for 868 * config success and report an error if it times out. 869 * If zero, no blocking or checking is performed. 870 * @return Period of the given status frame. 871 */ 872 public int getStatusFramePeriod(CANifierStatusFrame frame, int timeoutMs) { 873 return CANifierJNI.JNI_GetStatusFramePeriod(m_handle, frame.value, timeoutMs); 874 } 875 /** 876 * Gets the period of the given status frame. 877 * 878 * @param frame 879 * Frame to get the period of. 880 * @return Period of the given status frame. 881 */ 882 public int getStatusFramePeriod(CANifierStatusFrame frame) { 883 int timeoutMs = 0; 884 return getStatusFramePeriod(frame, timeoutMs); 885 } 886 887 /** 888 * Sets the period of the given control frame. 889 * 890 * @param frame 891 * Frame whose period is to be changed. 892 * @param periodMs 893 * Period in ms for the given frame. 894 * @return Error Code generated by function. 0 indicates no error. 895 */ 896 public ErrorCode setControlFramePeriod(CANifierControlFrame frame, int periodMs) { 897 int retval = CANifierJNI.JNI_SetControlFramePeriod(m_handle, frame.value, periodMs); 898 return ErrorCode.valueOf(retval); 899 } 900 /** 901 * Sets the period of the given control frame. 902 * 903 * @param frame 904 * Frame whose period is to be changed. 905 * @param periodMs 906 * Period in ms for the given frame. 907 * @return Error Code generated by function. 0 indicates no error. 908 */ 909 public ErrorCode setControlFramePeriod(int frame, int periodMs) { 910 int retval = CANifierJNI.JNI_SetControlFramePeriod(m_handle, frame, periodMs); 911 return ErrorCode.valueOf(retval); 912 } 913 914 /** 915 * Gets the firmware version of the device. 916 * 917 * @return Firmware version of device. 918 */ 919 public int getFirmwareVersion() { 920 return CANifierJNI.JNI_GetFirmwareVersion(m_handle); 921 } 922 923 /** 924 * Returns true if the device has reset since last call. 925 * 926 * @return Has a Device Reset Occurred? 927 */ 928 public boolean hasResetOccurred() { 929 return CANifierJNI.JNI_HasResetOccurred(m_handle); 930 } 931 932 // ------ Faults ----------// 933 /** 934 * Gets the CANifier fault status 935 * 936 * @param toFill 937 * Container for fault statuses. 938 * @return Error Code generated by function. 0 indicates no error. 939 */ 940 public ErrorCode getFaults(CANifierFaults toFill) { 941 int bits = CANifierJNI.JNI_GetFaults(m_handle); 942 toFill.update(bits); 943 return getLastError(); 944 } 945 /** 946 * Gets the CANifier sticky fault status 947 * 948 * @param toFill 949 * Container for sticky fault statuses. 950 * @return Error Code generated by function. 0 indicates no error. 951 */ 952 public ErrorCode getStickyFaults(CANifierStickyFaults toFill) { 953 int bits = CANifierJNI.JNI_GetStickyFaults(m_handle); 954 toFill.update(bits); 955 return getLastError(); 956 } 957 /** 958 * Clears the Sticky Faults 959 * 960 * @param timeoutMs 961 * Timeout value in ms. If nonzero, function will wait for 962 * config success and report an error if it times out. 963 * If zero, no blocking or checking is performed. 964 * 965 * @return Error Code generated by function. 0 indicates no error. 966 */ 967 public ErrorCode clearStickyFaults(int timeoutMs) { 968 int retval = CANifierJNI.JNI_ClearStickyFaults(m_handle, timeoutMs); 969 return ErrorCode.valueOf(retval); 970 } 971 972 /** 973 * Gets the bus voltage seen by the device. 974 * 975 * @return The bus voltage value (in volts). 976 */ 977 public double getBusVoltage() { 978 return CANifierJNI.JNI_GetBusVoltage(m_handle); 979 } 980 981 /** 982 * @return The Device Number 983 */ 984 public int getDeviceID(){ 985 return m_deviceNumber; 986 } 987 988 //------ All Configs ----------// 989 /** 990 * Configures all persistent settings. 991 * 992 * @param allConfigs Object with all of the persistant settings 993 * @param timeoutMs 994 * Timeout value in ms. If nonzero, function will wait for 995 * config success and report an error if it times out. 996 * If zero, no blocking or checking is performed. 997 * 998 * @return Error Code generated by function. 0 indicates no error. 999 */ 1000 public ErrorCode configAllSettings(CANifierConfiguration allConfigs, int timeoutMs) { 1001 ErrorCollection errorCollection = new ErrorCollection(); 1002 1003 errorCollection.NewError(configFactoryDefault(timeoutMs)); 1004 1005 if(CANifierConfigUtil.velocityMeasurementPeriodDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementPeriod(allConfigs.velocityMeasurementPeriod, timeoutMs)); 1006 if(CANifierConfigUtil.velocityMeasurementWindowDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementWindow(allConfigs.velocityMeasurementWindow, timeoutMs)); 1007 if(CANifierConfigUtil.clearPositionOnLimitFDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnLimitF(allConfigs.clearPositionOnLimitF, timeoutMs)); 1008 if(CANifierConfigUtil.clearPositionOnLimitRDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnLimitR(allConfigs.clearPositionOnLimitR, timeoutMs)); 1009 if(CANifierConfigUtil.clearPositionOnQuadIdxDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnQuadIdx(allConfigs.clearPositionOnQuadIdx, timeoutMs)); 1010 1011 //Custom Parameters 1012 if(CustomParamConfigUtil.customParam0Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam0, 0, timeoutMs)); 1013 if(CustomParamConfigUtil.customParam1Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam1, 1, timeoutMs)); 1014 1015 1016 return errorCollection._worstError; 1017 1018 } 1019 /** 1020 * Configures all persistent settings (overloaded so timeoutMs is 50 ms). 1021 * 1022 * @param allConfigs Object with all of the persistant settings 1023 * 1024 * @return Error Code generated by function. 0 indicates no error. 1025 */ 1026 public ErrorCode configAllSettings(CANifierConfiguration allConfigs) { 1027 int timeoutMs = 50; 1028 return configAllSettings(allConfigs, timeoutMs); 1029 } 1030 /** 1031 * Gets all persistant settings. 1032 * 1033 * @param allConfigs Object with all of the persistant settings 1034 * @param timeoutMs 1035 * Timeout value in ms. If nonzero, function will wait for 1036 * config success and report an error if it times out. 1037 * If zero, no blocking or checking is performed. 1038 */ 1039 public void getAllConfigs(CANifierConfiguration allConfigs, int timeoutMs) { 1040 1041 allConfigs.velocityMeasurementPeriod = VelocityPeriod.valueOf( (int) configGetParameter(ParamEnum.eSampleVelocityPeriod, 0, timeoutMs)); 1042 allConfigs.velocityMeasurementWindow = (int) configGetParameter(ParamEnum.eSampleVelocityWindow, 0, timeoutMs); 1043 allConfigs.clearPositionOnLimitF = configGetParameter(ParamEnum.eClearPositionOnLimitF, 0, timeoutMs) != 0.0; 1044 allConfigs.clearPositionOnLimitR = configGetParameter(ParamEnum.eClearPositionOnLimitR, 0, timeoutMs) != 0.0; 1045 allConfigs.clearPositionOnQuadIdx = configGetParameter(ParamEnum.eClearPositionOnQuadIdx, 0, timeoutMs) != 0.0; 1046 allConfigs.customParam0 = (int) configGetParameter(ParamEnum.eCustomParam, 0, timeoutMs); 1047 allConfigs.customParam1 = (int) configGetParameter(ParamEnum.eCustomParam, 1, timeoutMs); 1048 } 1049 /** 1050 * Gets all persistant settings (overloaded so timeoutMs is 50 ms). 1051 * 1052 * @param allConfigs Object with all of the persistant settings 1053 */ 1054 public void getAllConfigs(CANifierConfiguration allConfigs) { 1055 int timeoutMs = 50; 1056 getAllConfigs(allConfigs, timeoutMs); 1057 } 1058 /** 1059 * Configures all persistent settings to defaults. 1060 * 1061 * @param timeoutMs 1062 * Timeout value in ms. If nonzero, function will wait for 1063 * config success and report an error if it times out. 1064 * If zero, no blocking or checking is performed. 1065 * 1066 * @return Error Code generated by function. 0 indicates no error. 1067 */ 1068 public ErrorCode configFactoryDefault(int timeoutMs) { 1069 return ErrorCode.valueOf(CANifierJNI.JNI_ConfigFactoryDefault(m_handle, timeoutMs)); 1070 } 1071 /** 1072 * Configures all persistent settings to defaults (overloaded so timeoutMs is 50 ms). 1073 * 1074 * @return Error Code generated by function. 0 indicates no error. 1075 */ 1076 public ErrorCode configFactoryDefault() { 1077 int timeoutMs = 50; 1078 return configFactoryDefault( timeoutMs); 1079 } 1080 1081 1082}