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 */ 024package com.ctre.phoenix.sensors; 025import com.ctre.phoenix.ErrorCode; 026import com.ctre.phoenix.ErrorCollection; 027import com.ctre.phoenix.ParamEnum; 028import com.ctre.phoenix.sensors.CANCoderConfigUtil; 029 030/** 031 * CTRE CANCoder. 032 * 033 * <pre> 034 * {@code 035 * // Example usage of a CANCoder 036 * CANCoder cancoder = new CANCoder(0); // creates a new CANCoder with ID 0 037 * 038 * CANCoderConfiguration config = new CANCoderConfiguration(); 039 * // set units of the CANCoder to radians, with velocity being radians per second 040 * config.sensorCoefficient = 2 * Math.PI / 4096.0; 041 * config.unitString = "rad"; 042 * config.sensorTimeBase = SensorTimeBase.PerSecond; 043 * cancoder.configAllSettings(config); 044 * 045 * System.out.println(cancoder.getPosition()); // prints the position of the CANCoder 046 * System.out.println(cancoder.getVelocity()); // prints the velocity recorded by the CANCoder 047 * 048 * ErrorCode error = cancoder.getLastError(); // gets the last error generated by the CANCoder 049 * CANCoderFaults faults = new CANCoderFaults(); 050 * ErrorCode faultsError = cancoder.getFaults(faults); // fills faults with the current CANCoder faults; returns the last error generated 051 * 052 * cancoder.setStatusFramePeriod(CANCoderStatusFrame.SensorData, 10); // changes the period of the sensor data frame to 10ms 053 * } 054 * </pre> 055 * 056 * @deprecated This device's Phoenix 5 API is deprecated for removal in the 057 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the 058 * Phoenix 6 API. A migration guide is available at 059 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html. 060 * <p> 061 * If the Phoenix 5 API must be used for this device, the device must have 22.X 062 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in 063 * the firmware year dropdown. 064 */ 065@Deprecated(since = "2024", forRemoval = true) 066public class CANCoder{ 067 private long m_handle; 068 private CANCoderSimCollection m_simCollection; 069 070 private int m_deviceNumber; 071 072 /** 073 * Constructor. 074 * @param deviceNumber The CAN Device ID of the CANCoder. 075 * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux), 076 * or a CANivore device name or serial number 077 */ 078 public CANCoder(int deviceNumber, String canbus) { 079 m_handle = CANCoderJNI.Create(deviceNumber, canbus); 080 m_deviceNumber = deviceNumber; 081 m_simCollection = new CANCoderSimCollection(this); 082 } 083 084 /** 085 * Constructor. 086 * @param deviceNumber The CAN Device ID of the CANCoder. 087 */ 088 public CANCoder(int deviceNumber){ 089 this(deviceNumber, ""); 090 } 091 092 public ErrorCode DestroyObject() { 093 return ErrorCode.valueOf(CANCoderJNI.Destroy(m_handle)); 094 } 095 096 public int getDeviceID() { 097 return m_deviceNumber; 098 } 099 100 /** 101 * @return object that can set simulation inputs. 102 */ 103 public CANCoderSimCollection getSimCollection() { return m_simCollection; } 104 105 /** 106 * Gets the position of the sensor. This may be relative or absolute depending on configuration. 107 * The units are determined by the coefficient and unit-string configuration params, default is degrees. 108 * @return The position of the sensor. 109 */ 110 public double getPosition() { 111 return CANCoderJNI.GetPosition(m_handle); 112 } 113 /** 114 * Sets the position of the sensor. 115 * The units are determined by the coefficient and unit-string configuration params, default is degrees. 116 * @param newPosition 117 * @return ErrorCode generated by function. 0 indicates no error. 118 */ 119 public ErrorCode setPosition(double newPosition, int timeoutMs) { 120 return ErrorCode.valueOf(CANCoderJNI.SetPosition(m_handle, newPosition, timeoutMs)); 121 } 122 /** 123 * Sets the position of the sensor. 124 * The units are determined by the coefficient and unit-string configuration params, default is degrees. 125 * @param newPosition 126 * @return ErrorCode generated by function. 0 indicates no error. 127 */ 128 public ErrorCode setPosition(double newPosition) { 129 int timeoutMs = 0; 130 return ErrorCode.valueOf(CANCoderJNI.SetPosition(m_handle, newPosition, timeoutMs)); 131 } 132 /** 133 * Sets the position of the sensor to match the magnet's "Absolute Sensor". 134 * The units are determined by the coefficient and unit-string configuration params, default is degrees. 135 * @return ErrorCode generated by function. 0 indicates no error. 136 */ 137 public ErrorCode setPositionToAbsolute(int timeoutMs) { 138 return ErrorCode.valueOf(CANCoderJNI.SetPositionToAbsolute(m_handle, timeoutMs)); 139 } 140 /** 141 * Sets the position of the sensor to match the magnet's "Absolute Sensor". 142 * The units are determined by the coefficient and unit-string configuration params, default is degrees. 143 * @return ErrorCode generated by function. 0 indicates no error. 144 */ 145 public ErrorCode setPositionToAbsolute() { 146 int timeoutMs = 0; 147 return ErrorCode.valueOf(CANCoderJNI.SetPositionToAbsolute(m_handle, timeoutMs)); 148 } 149 /** 150 * Gets the velocity of the sensor. 151 * The units are determined by the coefficient and unit-string configuration params, default is degrees per second. 152 * @return The Velocity of the sensor. 153 */ 154 public double getVelocity() { 155 return CANCoderJNI.GetVelocity(m_handle); 156 } 157 /** 158 * Gets the absolute position of the sensor. 159 * The absolute position may be unsigned (for example: [0,360) deg), or signed (for example: [-180,+180) deg). This is determined by a configuration. The default selection is unsigned. 160 * The units are determined by the coefficient and unit-string configuration params, default is degrees. 161 * Note: this signal is not affected by calls to SetPosition(). 162 * @return The position of the sensor. 163 */ 164 public double getAbsolutePosition() { 165 return CANCoderJNI.GetAbsolutePosition(m_handle); 166 } 167 /** 168 * Configures the period of each velocity sample. 169 * Every 1ms a position value is sampled, and the delta between that sample 170 * and the position sampled kPeriod ms ago is inserted into a filter. 171 * kPeriod is configured with this function. 172 * 173 * @param period 174 * Desired period for the velocity measurement. 175 * @param timeoutMs 176 * Timeout value in ms. If nonzero, function will wait for 177 * config success and report an error if it times out. 178 * If zero, no blocking or checking is performed. 179 * @return Error Code generated by function. 0 indicates no error. 180 */ 181 public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs) { 182 return ErrorCode.valueOf(CANCoderJNI.ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs)); 183 } 184 /** 185 * Configures the period of each velocity sample. 186 * Every 1ms a position value is sampled, and the delta between that sample 187 * and the position sampled kPeriod ms ago is inserted into a filter. 188 * kPeriod is configured with this function. 189 * 190 * @param period 191 * Desired period for the velocity measurement. 192 * @return Error Code generated by function. 0 indicates no error. 193 */ 194 public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period) { 195 int timeoutMs = 0; 196 return configVelocityMeasurementPeriod(period, timeoutMs); 197 } 198 /** 199 * Sets the number of velocity samples used in the rolling average velocity 200 * measurement. 201 * 202 * @param windowSize 203 * Number of samples in the rolling average of velocity 204 * measurement. Valid values are 1,2,4,8,16,32. If another 205 * value is specified, it will truncate to nearest support value. 206 * @param timeoutMs 207 * Timeout value in ms. If nonzero, function will wait for 208 * config success and report an error if it times out. 209 * If zero, no blocking or checking is performed. 210 * @return Error Code generated by function. 0 indicates no error. 211 */ 212 public ErrorCode configVelocityMeasurementWindow(int windowSize, int timeoutMs) { 213 return ErrorCode.valueOf(CANCoderJNI.ConfigVelocityMeasurementWindow(m_handle, windowSize, timeoutMs)); 214 } 215 /** 216 * Sets the number of velocity samples used in the rolling average velocity 217 * measurement. 218 * 219 * @param windowSize 220 * Number of samples in the rolling average of velocity 221 * measurement. Valid values are 1,2,4,8,16,32. If another 222 * value is specified, it will truncate to nearest support value. 223 * @return Error Code generated by function. 0 indicates no error. 224 */ 225 public ErrorCode configVelocityMeasurementWindow(int windowSize) { 226 int timeoutMs = 0; 227 return configVelocityMeasurementWindow(windowSize, timeoutMs); 228 } 229 /** 230 * Sets the signage and range of the "Absolute Position" signal. 231 * Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc... 232 * Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc... 233 * @param absoluteSensorRange 234 * Desired Sign/Range for the absolute position register. 235 * @param timeoutMs 236 * Timeout value in ms. If nonzero, function will wait for 237 * config success and report an error if it times out. 238 * If zero, no blocking or checking is performed. 239 * @return Error Code generated by function. 0 indicates no error. 240 */ 241 public ErrorCode configAbsoluteSensorRange(AbsoluteSensorRange absoluteSensorRange, int timeoutMs) 242 { 243 return ErrorCode.valueOf(CANCoderJNI.ConfigAbsoluteSensorRange(m_handle, absoluteSensorRange.value, timeoutMs)); 244 } 245 /** 246 * Sets the signage and range of the "Absolute Position" signal. 247 * Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc... 248 * Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc... 249 * @param absoluteSensorRange 250 * Desired Sign/Range for the absolute position register. 251 * @return Error Code generated by function. 0 indicates no error. 252 */ 253 public ErrorCode configAbsoluteSensorRange(AbsoluteSensorRange absoluteSensorRange) 254 { 255 int timeoutMs = 0; 256 return configAbsoluteSensorRange(absoluteSensorRange, timeoutMs); 257 } 258 /** 259 * Adjusts the zero point for the absolute position register. 260 * The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) 261 * and a hard-limited mechanism may have such a discontinuity in its functional range. 262 * In which case use this config to move the discontinuity outside of the function range. 263 * @param offsetDegrees 264 * Offset in degrees (unit string and coefficient DO NOT apply for this config). 265 * @param timeoutMs 266 * Timeout value in ms. If nonzero, function will wait for 267 * config success and report an error if it times out. 268 * If zero, no blocking or checking is performed. 269 * @return Error Code generated by function. 0 indicates no error. 270 */ 271 public ErrorCode configMagnetOffset(double offsetDegrees, int timeoutMs) 272 { 273 return ErrorCode.valueOf(CANCoderJNI.ConfigMagnetOffset(m_handle, offsetDegrees, timeoutMs)); 274 } 275 /** 276 * Adjusts the zero point for the absolute position register. 277 * The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) 278 * and a hard-limited mechanism may have such a discontinuity in its functional range. 279 * In which case use this config to move the discontinuity outside of the function range. 280 * @param offsetDegrees 281 * Offset in degrees (unit string and coefficient DO NOT apply for this config). 282 * @return Error Code generated by function. 0 indicates no error. 283 */ 284 public ErrorCode configMagnetOffset(double offsetDegrees) 285 { 286 int timeoutMs = 0; 287 return configMagnetOffset(offsetDegrees, timeoutMs); 288 } 289 /** 290 * Pick the strategy on how to initialize the CANCoder's "Position" register. Depending on the mechanism, 291 * it may be desirable to auto set the Position register to match the Absolute Position (swerve for example). 292 * Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo). 293 * 294 * TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the CANCoder is reset. 295 * 296 * @param initializationStrategy 297 * The sensor initialization strategy to use. This will impact the behavior the next time CANCoder boots up. 298 * @param timeoutMs 299 * Timeout value in ms. If nonzero, function will wait for 300 * config success and report an error if it times out. 301 * If zero, no blocking or checking is performed. 302 * @return Error Code generated by function. 0 indicates no error. 303 */ 304 public ErrorCode configSensorInitializationStrategy(SensorInitializationStrategy initializationStrategy, int timeoutMs) 305 { 306 return ErrorCode.valueOf(CANCoderJNI.ConfigSensorInitializationStrategy(m_handle, initializationStrategy.value, timeoutMs)); 307 } 308 /** 309 * Pick the strategy on how to initialize the CANCoder's "Position" register. Depending on the mechanism, 310 * it may be desirable to auto set the Position register to match the Absolute Position (swerve for example). 311 * Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo). 312 * 313 * TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the CANCoder is reset. 314 * 315 * @param initializationStrategy 316 * The sensor initialization strategy to use. This will impact the behavior the next time CANCoder boots up. 317 * @return Error Code generated by function. 0 indicates no error. 318 */ 319 public ErrorCode configSensorInitializationStrategy(SensorInitializationStrategy initializationStrategy) 320 { 321 int timeoutMs = 0; 322 return configSensorInitializationStrategy(initializationStrategy, timeoutMs); 323 } 324 /** 325 * Choose what units you want the API to get/set. This also impacts the units displayed in Self-Test in Tuner. 326 * Depending on your mechanism, you may want to scale rotational units (deg, radians, rotations), or scale to a distance (inches, centimeters). 327 * @param sensorCoefficient 328 * Scalar to multiply the CANCoder's native 12-bit resolute sensor. Defaults to 0.087890625 to produce degrees. 329 * @param unitString 330 * String holding the unit to report in. This impacts all routines (except for ConfigMagnetOffset) and the self-test in Tuner. 331 * The string value itself is arbitrary. The max number of letters will depend on firmware versioning, but generally CANCoder 332 * supports up to eight letters. However, common units such as "centimeters" are supported explicitly despite exceeding the eight-letter limit. 333 * Default is "deg" 334 * @param sensorTimeBase 335 * Desired denominator to report velocity in. This impacts GetVelocity and the reported velocity in self-test in Tuner. 336 * Default is "Per Second". 337 * @param timeoutMs 338 * Timeout value in ms. If nonzero, function will wait for 339 * config success and report an error if it times out. 340 * If zero, no blocking or checking is performed. 341 * @return Error Code generated by function. 0 indicates no error. 342 */ 343 public ErrorCode configFeedbackCoefficient(double sensorCoefficient, String unitString, SensorTimeBase sensorTimeBase, int timeoutMs) 344 { 345 return ErrorCode.valueOf(CANCoderJNI.ConfigFeedbackCoefficient(m_handle, sensorCoefficient, unitString, sensorTimeBase.value, timeoutMs)); 346 } 347 /** 348 * Choose what units you want the API to get/set. This also impacts the units displayed in Self-Test in Tuner. 349 * Depending on your mechanism, you may want to scale rotational units (deg, radians, rotations), or scale to a distance (inches, centimeters). 350 * @param sensorCoefficient 351 * Scalar to multiply the CANCoder's native 12-bit resolute sensor. Defaults to 0.087890625 to produce degrees. 352 * @param unitString 353 * String holding the unit to report in. This impacts all routines (except for ConfigMagnetOffset) and the self-test in Tuner. 354 * The string value itself is arbitrary. The max number of letters will depend on firmware versioning, but generally CANCoder 355 * supports up to eight letters. However, common units such as "centimeters" are supported explicitly despite exceeding the eight-letter limit. 356 * Default is "deg" 357 * @param sensorTimeBase 358 * Desired denominator to report velocity in. This impacts GetVelocity and the reported velocity in self-test in Tuner. 359 * Default is "Per Second". 360 * @return Error Code generated by function. 0 indicates no error. 361 */ 362 public ErrorCode configFeedbackCoefficient(double sensorCoefficient, String unitString, SensorTimeBase sensorTimeBase) 363 { 364 int timeoutMs = 0; 365 return configFeedbackCoefficient(sensorCoefficient, unitString, sensorTimeBase, timeoutMs); 366 } 367 /** 368 * Gets the bus voltage seen by the device. 369 * 370 * @return The bus voltage value (in volts). 371 */ 372 public double getBusVoltage() { 373 return CANCoderJNI.GetBusVoltage(m_handle); 374 } 375 /** 376 * Gets the magnet's health. 377 * 378 * @return The magnet health code (red/orange/green). 379 */ 380 public MagnetFieldStrength getMagnetFieldStrength() { 381 return MagnetFieldStrength.valueOf(CANCoderJNI.GetMagnetFieldStrength(m_handle)); 382 } 383 /** 384 * Choose which direction is interpreted as positive displacement. 385 * This affects both "Position" and "Absolute Position". 386 * @param bSensorDirection 387 * False (default) means positive rotation occurs when magnet 388 * is spun counter-clockwise when observer is facing the LED side of CANCoder. 389 * @param timeoutMs 390 * Timeout value in ms. If nonzero, function will wait for 391 * config success and report an error if it times out. 392 * If zero, no blocking or checking is performed. 393 * @return Error Code generated by function. 0 indicates no error. 394 */ 395 public ErrorCode configSensorDirection(boolean bSensorDirection, int timeoutMs) 396 { 397 return ErrorCode.valueOf(CANCoderJNI.ConfigSensorDirection(m_handle, bSensorDirection ? 1:0, timeoutMs)); 398 } 399 /** 400 * Choose which direction is interpreted as positive displacement. 401 * This affects both "Position" and "Absolute Position". 402 * @param bSensorDirection 403 * False (default) means positive rotation occurs when magnet 404 * is spun counter-clockwise when observer is facing the LED side of CANCoder. 405 * @return Error Code generated by function. 0 indicates no error. 406 */ 407 public ErrorCode configSensorDirection(boolean bSensorDirection) 408 { 409 int timeoutMs = 0; 410 return configSensorDirection(bSensorDirection, timeoutMs); 411 } 412 /** 413 * Call GetLastError() generated by this object. 414 * Not all functions return an error code but can 415 * potentially report errors. 416 * 417 * This function can be used to retrieve those error codes. 418 * 419 * @return The last ErrorCode generated. 420 */ 421 public ErrorCode getLastError() { 422 return ErrorCode.valueOf(CANCoderJNI.GetLastError(m_handle)); 423 } 424 425 /** 426 * Get the units for the signal retrieved in the last called get routine. 427 */ 428 public String getLastUnitString() { 429 return CANCoderJNI.GetLastUnitString(m_handle); 430 } 431 432 /** 433 * Get the timestamp of the CAN frame retrieved in the last called get routine. 434 */ 435 public double getLastTimestamp() { 436 return CANCoderJNI.GetLastTimestamp(m_handle); 437 } 438 439 //------ Custom Persistent Params ----------// 440 441 /** 442 * Sets the value of a custom parameter. This is for arbitrary use. 443 * 444 * Sometimes it is necessary to save calibration/duty cycle/output 445 * information in the device. Particularly if the 446 * device is part of a subsystem that can be replaced. 447 * 448 * @param newValue 449 * Value for custom parameter. 450 * @param paramIndex 451 * Index of custom parameter. [0-1] 452 * @param timeoutMs 453 * Timeout value in ms. If nonzero, function will wait for 454 * config success and report an error if it times out. 455 * If zero, no blocking or checking is performed. 456 * @return Error Code generated by function. 0 indicates no error. 457 */ 458 public ErrorCode configSetCustomParam(int newValue, 459 int paramIndex, int timeoutMs) { 460 return ErrorCode.valueOf(CANCoderJNI.ConfigSetCustomParam(m_handle, newValue, paramIndex, timeoutMs)); 461 } 462 /** 463 * Sets the value of a custom parameter. This is for arbitrary use. 464 * 465 * Sometimes it is necessary to save calibration/duty cycle/output 466 * information in the device. Particularly if the 467 * device is part of a subsystem that can be replaced. 468 * 469 * @param newValue 470 * Value for custom parameter. 471 * @param paramIndex 472 * Index of custom parameter. [0-1] 473 * @return Error Code generated by function. 0 indicates no error. 474 */ 475 public ErrorCode configSetCustomParam(int newValue, 476 int paramIndex) { 477 int timeoutMs = 0; 478 return configSetCustomParam(newValue, paramIndex, timeoutMs); 479 } 480 /** 481 * Gets the value of a custom parameter. This is for arbitrary use. 482 * 483 * Sometimes it is necessary to save calibration/duty cycle/output 484 * information in the device. Particularly if the 485 * device is part of a subsystem that can be replaced. 486 * 487 * @param paramIndex 488 * Index of custom parameter. [0-1] 489 * @param timeoutMs 490 * Timeout value in ms. If nonzero, function will wait for 491 * config success and report an error if it times out. 492 * If zero, no blocking or checking is performed. 493 * @return Value of the custom param. 494 */ 495 public int configGetCustomParam(int paramIndex, int timeoutMs) { 496 return CANCoderJNI.ConfigGetCustomParam(m_handle, paramIndex, timeoutMs); 497 } 498 /** 499 * Gets the value of a custom parameter. This is for arbitrary use. 500 * 501 * Sometimes it is necessary to save calibration/duty cycle/output 502 * information in the device. Particularly if the 503 * device is part of a subsystem that can be replaced. 504 * 505 * @param paramIndex 506 * Index of custom parameter. [0-1] 507 * @return Value of the custom param. 508 */ 509 public int configGetCustomParam(int paramIndex) { 510 int timeoutMs = 0; 511 return configGetCustomParam(paramIndex, timeoutMs); 512 } 513 514 //------ Generic Param API, typically not used ----------// 515 /** 516 * Sets a parameter. Generally this is not used. 517 * This can be utilized in 518 * - Using new features without updating API installation. 519 * - Errata workarounds to circumvent API implementation. 520 * - Allows for rapid testing / unit testing of firmware. 521 * 522 * @param param 523 * Parameter enumeration. 524 * @param value 525 * Value of parameter. 526 * @param subValue 527 * Subvalue for parameter. Maximum value of 255. 528 * @param ordinal 529 * Ordinal of parameter. 530 * @param timeoutMs 531 * Timeout value in ms. If nonzero, function will wait for 532 * config success and report an error if it times out. 533 * If zero, no blocking or checking is performed. 534 * @return Error Code generated by function. 0 indicates no error. 535 */ 536 public ErrorCode configSetParameter(ParamEnum param, double value, 537 int subValue, int ordinal, int timeoutMs) { 538 return ErrorCode.valueOf(CANCoderJNI.ConfigSetParameter(m_handle, param.value, value, subValue, ordinal, timeoutMs)); 539 540 } 541 /** 542 * Sets a parameter. Generally this is not used. 543 * This can be utilized in 544 * - Using new features without updating API installation. 545 * - Errata workarounds to circumvent API implementation. 546 * - Allows for rapid testing / unit testing of firmware. 547 * 548 * @param param 549 * Parameter enumeration. 550 * @param value 551 * Value of parameter. 552 * @param subValue 553 * Subvalue for parameter. Maximum value of 255. 554 * @param ordinal 555 * Ordinal of parameter. 556 * @return Error Code generated by function. 0 indicates no error. 557 */ 558 public ErrorCode configSetParameter(ParamEnum param, double value, 559 int subValue, int ordinal) { 560 int timeoutMs = 0; 561 return configSetParameter(param, value, subValue, ordinal, timeoutMs); 562 563 } 564 /** 565 * Gets a parameter. Generally this is not used. 566 * This can be utilized in 567 * - Using new features without updating API installation. 568 * - Errata workarounds to circumvent API implementation. 569 * - Allows for rapid testing / unit testing of firmware. 570 * 571 * @param param 572 * Parameter enumeration. 573 * @param ordinal 574 * Ordinal of parameter. 575 * @param timeoutMs 576 * Timeout value in ms. If nonzero, function will wait for 577 * config success and report an error if it times out. 578 * If zero, no blocking or checking is performed. 579 * @return Value of parameter. 580 */ 581 public double configGetParameter(ParamEnum param, int ordinal, int timeoutMs) { 582 return CANCoderJNI.ConfigGetParameter(m_handle, param.value, ordinal, timeoutMs); 583 } 584 /** 585 * Gets a parameter. Generally this is not used. 586 * This can be utilized in 587 * - Using new features without updating API installation. 588 * - Errata workarounds to circumvent API implementation. 589 * - Allows for rapid testing / unit testing of firmware. 590 * 591 * @param param 592 * Parameter enumeration. 593 * @param ordinal 594 * Ordinal of parameter. 595 * @return Value of parameter. 596 */ 597 public double configGetParameter(ParamEnum param, int ordinal) { 598 int timeoutMs = 0; 599 return configGetParameter(param, ordinal, timeoutMs); 600 } 601 602 //------ Frames ----------// 603 /** 604 * Sets the period of the given status frame. 605 * 606 * @param statusFrame 607 * Frame whose period is to be changed. 608 * @param periodMs 609 * Period in ms for the given frame. 610 * @param timeoutMs 611 * Timeout value in ms. If nonzero, function will wait for 612 * config success and report an error if it times out. 613 * If zero, no blocking or checking is performed. 614 * @return Error Code generated by function. 0 indicates no error. 615 */ 616 public ErrorCode setStatusFramePeriod(CANCoderStatusFrame statusFrame, int periodMs, int timeoutMs) { 617 return ErrorCode.valueOf(CANCoderJNI.SetStatusFramePeriod(m_handle, statusFrame.value, periodMs, timeoutMs)); 618 } 619 /** 620 * Sets the period of the given status frame. 621 * 622 * @param statusFrame 623 * Frame whose period is to be changed. 624 * @param periodMs 625 * Period in ms for the given frame. 626 * @return Error Code generated by function. 0 indicates no error. 627 */ 628 public ErrorCode setStatusFramePeriod(CANCoderStatusFrame statusFrame, int periodMs) { 629 int timeoutMs = 0; 630 return setStatusFramePeriod(statusFrame, periodMs, timeoutMs); 631 } 632 /** 633 * Gets the period of the given status frame. 634 * 635 * @param frame 636 * Frame to get the period of. 637 * @param timeoutMs 638 * Timeout value in ms. If nonzero, function will wait for 639 * config success and report an error if it times out. 640 * If zero, no blocking or checking is performed. 641 * @return Period of the given status frame. 642 */ 643 public int getStatusFramePeriod(CANCoderStatusFrame frame, 644 int timeoutMs) { 645 return CANCoderJNI.GetStatusFramePeriod(m_handle, frame.value, timeoutMs); 646 } 647 /** 648 * Gets the period of the given status frame. 649 * 650 * @param frame 651 * Frame to get the period of. 652 * @return Period of the given status frame. 653 */ 654 public int getStatusFramePeriod(CANCoderStatusFrame frame) { 655 int timeoutMs = 0; 656 return getStatusFramePeriod(frame, timeoutMs); 657 } 658 //------ Firmware ----------// 659 /** 660 * Gets the firmware version of the device. 661 * 662 * @return Firmware version of device. 663 */ 664 public int getFirmwareVersion() { 665 return CANCoderJNI.GetFirmwareVersion(m_handle); 666 } 667 /** 668 * Returns true if the device has reset since last call. 669 * 670 * @return Has a Device Reset Occurred? 671 */ 672 public boolean hasResetOccurred() { 673 return CANCoderJNI.HasResetOccurred(m_handle); 674 } 675 //------ Faults ----------// 676 /** 677 * Gets the CANCoder fault status 678 * 679 * @param toFill 680 * Container for fault statuses. 681 * @return Error Code generated by function. 0 indicates no error. 682 */ 683 public ErrorCode getFaults(CANCoderFaults toFill) { 684 int bits = CANCoderJNI.GetFaults(m_handle); 685 toFill.update(bits); 686 return getLastError(); 687 } 688 /** 689 * Gets the CANCoder sticky fault status 690 * 691 * @param toFill 692 * Container for sticky fault statuses. 693 * @return Error Code generated by function. 0 indicates no error. 694 */ 695 public ErrorCode getStickyFaults(CANCoderStickyFaults toFill) { 696 int bits = CANCoderJNI.GetStickyFaults(m_handle); 697 toFill.update(bits); 698 return getLastError(); 699 } 700 /** 701 * Clears the Sticky Faults 702 * 703 * @return Error Code generated by function. 0 indicates no error. 704 */ 705 public ErrorCode clearStickyFaults(int timeoutMs) { 706 return ErrorCode.valueOf(CANCoderJNI.ClearStickyFaults(m_handle, timeoutMs)); 707 } 708 /** 709 * Clears the Sticky Faults 710 * 711 * @return Error Code generated by function. 0 indicates no error. 712 */ 713 public ErrorCode clearStickyFaults() { 714 int timeoutMs = 0; 715 return clearStickyFaults(timeoutMs); 716 } 717 718 /** 719 * 720 * @param timeoutMs 721 * Timeout value in ms. If nonzero, function will wait for 722 * config success and report an error if it times out. 723 * @return Read value of the config param. 724 */ 725 public SensorVelocityMeasPeriod configGetVelocityMeasurementPeriod(int timeoutMs) 726 { 727 return SensorVelocityMeasPeriod.valueOf(CANCoderJNI.ConfigGetVelocityMeasurementPeriod(m_handle, timeoutMs)); 728 } 729 /** 730 * @return Read value of the config param. 731 */ 732 public SensorVelocityMeasPeriod configGetVelocityMeasurementPeriod() 733 { 734 int timeoutMs = 50; 735 return configGetVelocityMeasurementPeriod(timeoutMs); 736 } 737 /** 738 * 739 * @param timeoutMs 740 * Timeout value in ms. If nonzero, function will wait for 741 * config success and report an error if it times out. 742 * @return Read value of the config param. 743 */ 744 public int configGetVelocityMeasurementWindow(int timeoutMs) 745 { 746 return CANCoderJNI.ConfigGetVelocityMeasurementWindow(m_handle, timeoutMs); 747 } 748 /** 749 * @return Read value of the config param. 750 */ 751 public int configGetVelocityMeasurementWindow() 752 { 753 int timeoutMs = 50; 754 return configGetVelocityMeasurementWindow(timeoutMs); 755 } 756 /** 757 * 758 * @param timeoutMs 759 * Timeout value in ms. If nonzero, function will wait for 760 * config success and report an error if it times out. 761 * @return Read value of the config param. 762 */ 763 public AbsoluteSensorRange configGetAbsoluteSensorRange(int timeoutMs) 764 { 765 return AbsoluteSensorRange.valueOf(CANCoderJNI.ConfigGetAbsoluteSensorRange(m_handle, timeoutMs)); 766 } 767 /** 768 * @return Read value of the config param. 769 */ 770 public AbsoluteSensorRange configGetAbsoluteSensorRange() 771 { 772 int timeoutMs = 50; 773 return configGetAbsoluteSensorRange(timeoutMs); 774 } 775 /** 776 * 777 * @param timeoutMs 778 * Timeout value in ms. If nonzero, function will wait for 779 * config success and report an error if it times out. 780 * @return Read value of the config param. 781 */ 782 public double configGetMagnetOffset(int timeoutMs) 783 { 784 return CANCoderJNI.ConfigGetMagnetOffset(m_handle, timeoutMs); 785 } 786 /** 787 * @return Read value of the config param. 788 */ 789 public double configGetMagnetOffset() 790 { 791 int timeoutMs = 50; 792 return configGetMagnetOffset(timeoutMs); 793 } 794 /** 795 * 796 * @param timeoutMs 797 * Timeout value in ms. If nonzero, function will wait for 798 * config success and report an error if it times out. 799 * @return Read value of the config param. 800 */ 801 public boolean configGetSensorDirection(int timeoutMs) 802 { 803 return 0 != CANCoderJNI.ConfigGetSensorDirection(m_handle, timeoutMs); 804 } 805 /** 806 * @return Read value of the config param. 807 */ 808 public boolean configGetSensorDirection() 809 { 810 int timeoutMs = 50; 811 return configGetSensorDirection(timeoutMs); 812 } 813 /** 814 * 815 * @param timeoutMs 816 * Timeout value in ms. If nonzero, function will wait for 817 * config success and report an error if it times out. 818 * @return Read value of the config param. 819 */ 820 public SensorInitializationStrategy configGetSensorInitializationStrategy(int timeoutMs) 821 { 822 return SensorInitializationStrategy.valueOf(CANCoderJNI.ConfigGetSensorInitializationStrategy(m_handle, timeoutMs)); 823 } 824 /** 825 * @return Read value of the config param. 826 */ 827 public SensorInitializationStrategy configGetSensorInitializationStrategy() 828 { 829 int timeoutMs = 50; 830 return configGetSensorInitializationStrategy(timeoutMs); 831 } 832 /** 833 * 834 * @param timeoutMs 835 * Timeout value in ms. If nonzero, function will wait for 836 * config success and report an error if it times out. 837 * @return Read value of the config param. 838 */ 839 public double configGetFeedbackCoefficient(int timeoutMs) 840 { 841 return CANCoderJNI.ConfigGetFeedbackCoefficient(m_handle, timeoutMs); 842 } 843 /** 844 * @return Read value of the config param. 845 */ 846 public double configGetFeedbackCoefficient() 847 { 848 int timeoutMs = 50; 849 return configGetFeedbackCoefficient(timeoutMs); 850 } 851 /** 852 * 853 * @param timeoutMs 854 * Timeout value in ms. If nonzero, function will wait for 855 * config success and report an error if it times out. 856 * @return Read value of the config param. 857 */ 858 public String configGetFeedbackUnitString(int timeoutMs) 859 { 860 return CANCoderJNI.ConfigGetFeedbackUnitString(m_handle, timeoutMs); 861 } 862 /** 863 * @return Read value of the config param. 864 */ 865 public String configGetFeedbackUnitString() 866 { 867 int timeoutMs = 50; 868 return configGetFeedbackUnitString(timeoutMs); 869 } 870 /** 871 * 872 * @param timeoutMs 873 * Timeout value in ms. If nonzero, function will wait for 874 * config success and report an error if it times out. 875 * @return Read value of the config param. 876 */ 877 public SensorTimeBase configGetFeedbackTimeBase(int timeoutMs) 878 { 879 return SensorTimeBase.valueOf(CANCoderJNI.ConfigGetFeedbackTimeBase(m_handle, timeoutMs)); 880 } 881 /** 882 * @return Read value of the config param. 883 */ 884 public SensorTimeBase configGetFeedbackTimeBase() 885 { 886 int timeoutMs = 50; 887 return configGetFeedbackTimeBase(timeoutMs); 888 } 889 890 /** 891 * Configures all persistent settings. 892 * 893 * @param allConfigs Object with all of the persistant settings 894 * @param timeoutMs 895 * Timeout value in ms. If nonzero, function will wait for 896 * config success and report an error if it times out. 897 * If zero, no blocking or checking is performed. 898 * 899 * @return Error Code generated by function. 0 indicates no error. 900 */ 901 public ErrorCode configAllSettings(CANCoderConfiguration allConfigs, int timeoutMs) { 902 903 ErrorCollection errorCollection = new ErrorCollection(); 904 errorCollection.NewError(configFactoryDefault(timeoutMs)); 905 906 if (CANCoderConfigUtil.velocityMeasurementPeriodDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementPeriod(allConfigs.velocityMeasurementPeriod, timeoutMs)); 907 if (CANCoderConfigUtil.velocityMeasurementWindowDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementWindow(allConfigs.velocityMeasurementWindow, timeoutMs)); 908 if (CANCoderConfigUtil.customParam0Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam0, 0, timeoutMs)); 909 if (CANCoderConfigUtil.customParam1Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam1, 1, timeoutMs)); 910 if (CANCoderConfigUtil.absoluteSensorRangeDifferent(allConfigs)) errorCollection.NewError(configAbsoluteSensorRange(allConfigs.absoluteSensorRange, timeoutMs)); 911 if (CANCoderConfigUtil.magnetOffsetDegreesDifferent(allConfigs)) errorCollection.NewError(configMagnetOffset(allConfigs.magnetOffsetDegrees, timeoutMs)); 912 if (CANCoderConfigUtil.sensorDirectionDifferent(allConfigs)) errorCollection.NewError(configSensorDirection(allConfigs.sensorDirection, timeoutMs)); 913 if (CANCoderConfigUtil.initializationStrategyDifferent(allConfigs)) errorCollection.NewError(configSensorInitializationStrategy(allConfigs.initializationStrategy, timeoutMs)); 914 if (CANCoderConfigUtil.sensorCoefficientDifferent(allConfigs) || 915 CANCoderConfigUtil.unitStringDifferent(allConfigs) || 916 CANCoderConfigUtil.sensorTimeBaseDifferent(allConfigs)) { 917 errorCollection.NewError(configFeedbackCoefficient(allConfigs.sensorCoefficient, allConfigs.unitString, allConfigs.sensorTimeBase, timeoutMs)); 918 } 919 920 return errorCollection._worstError; 921 } 922 /** 923 * Configures all persistent settings (overloaded so timeoutMs is 50 ms). 924 * 925 * @param allConfigs Object with all of the persistant settings 926 * 927 * @return Error Code generated by function. 0 indicates no error. 928 */ 929 public ErrorCode configAllSettings(CANCoderConfiguration allConfigs) { 930 int timeoutMs = 50; 931 return configAllSettings(allConfigs, timeoutMs); 932 } 933 934 /** 935 * Gets all persistant settings. 936 * 937 * @param allConfigs Object with all of the persistant settings 938 * @param timeoutMs 939 * Timeout value in ms. If nonzero, function will wait for 940 * config success and report an error if it times out. 941 * If zero, no blocking or checking is performed. 942 */ 943 public void getAllConfigs(CANCoderConfiguration allConfigs, int timeoutMs) { 944 allConfigs.velocityMeasurementPeriod = configGetVelocityMeasurementPeriod(timeoutMs); 945 allConfigs.velocityMeasurementWindow = configGetVelocityMeasurementWindow(timeoutMs); 946 allConfigs.customParam0 = (int)configGetParameter(ParamEnum.eCustomParam, 0, timeoutMs); 947 allConfigs.customParam1 = (int)configGetParameter(ParamEnum.eCustomParam, 1, timeoutMs); 948 allConfigs.absoluteSensorRange = configGetAbsoluteSensorRange(timeoutMs); 949 allConfigs.magnetOffsetDegrees = configGetMagnetOffset(timeoutMs); 950 allConfigs.sensorDirection = configGetSensorDirection(timeoutMs); 951 allConfigs.initializationStrategy = configGetSensorInitializationStrategy(timeoutMs); 952 allConfigs.sensorCoefficient = configGetFeedbackCoefficient(timeoutMs); 953 allConfigs.unitString = configGetFeedbackUnitString(timeoutMs); 954 allConfigs.sensorTimeBase = configGetFeedbackTimeBase(timeoutMs); 955 } 956 /** 957 * Gets all persistant settings (overloaded so timeoutMs is 50 ms). 958 * 959 * @param allConfigs Object with all of the persistant settings 960 */ 961 public void getAllConfigs(CANCoderConfiguration allConfigs) { 962 int timeoutMs = 50; 963 getAllConfigs(allConfigs, timeoutMs); 964 } 965 966 /** 967 * Configures all persistent settings to defaults. 968 * 969 * @param timeoutMs 970 * Timeout value in ms. If nonzero, function will wait for 971 * config success and report an error if it times out. 972 * If zero, no blocking or checking is performed. 973 * 974 * @return Error Code generated by function. 0 indicates no error. 975 */ 976 public ErrorCode configFactoryDefault(int timeoutMs) { 977 return ErrorCode.valueOf(CANCoderJNI.ConfigFactoryDefault(m_handle, timeoutMs)); 978 } 979 /** 980 * Configures all persistent settings to defaults. 981 * 982 * @return Error Code generated by function. 0 indicates no error. 983 */ 984 public ErrorCode configFactoryDefault() { 985 int timeoutMs = 50; 986 return configFactoryDefault(timeoutMs); 987 } 988}