001/* Copyright (C) Cross The Road Electronics 2024 */ 002package com.ctre.phoenix.motorcontrol.can; 003 004import com.ctre.phoenix.motorcontrol.ControlFrame; 005import com.ctre.phoenix.motorcontrol.ControlMode; 006import com.ctre.phoenix.motorcontrol.DemandType; 007import com.ctre.phoenix.motorcontrol.Faults; 008import com.ctre.phoenix.motorcontrol.FeedbackDevice; 009import com.ctre.phoenix.motorcontrol.FollowerType; 010import com.ctre.phoenix.motorcontrol.IMotorController; 011import com.ctre.phoenix.motorcontrol.InvertType; 012import com.ctre.phoenix.motorcontrol.LimitSwitchNormal; 013import com.ctre.phoenix.motorcontrol.LimitSwitchSource; 014import com.ctre.phoenix.motorcontrol.NeutralMode; 015import com.ctre.phoenix.motorcontrol.RemoteFeedbackDevice; 016import com.ctre.phoenix.motorcontrol.RemoteLimitSwitchSource; 017import com.ctre.phoenix.motorcontrol.RemoteSensorSource; 018import com.ctre.phoenix.motorcontrol.SensorTerm; 019import com.ctre.phoenix.motorcontrol.StatusFrame; 020import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced; 021import com.ctre.phoenix.motorcontrol.StickyFaults; 022import com.ctre.phoenix.motorcontrol.VelocityMeasPeriod; 023import com.ctre.phoenix.motorcontrol.VictorSPXSimCollection; 024import com.ctre.phoenix.ParamEnum; 025import com.ctre.phoenix.motion.BufferedTrajectoryPointStream; 026import com.ctre.phoenix.motion.MotionProfileStatus; 027import com.ctre.phoenix.motion.SetValueMotionProfile; 028import com.ctre.phoenix.motion.TrajectoryPoint; 029import com.ctre.phoenix.ErrorCode; 030import com.ctre.phoenix.ErrorCollection; 031import com.ctre.phoenix.ParamEnum; 032import com.ctre.phoenix.sensors.SensorVelocityMeasPeriod; 033 034/** 035 * Base motor controller features for all CTRE CAN motor controllers. 036 */ 037public abstract class BaseMotorController implements com.ctre.phoenix.motorcontrol.IMotorController { 038 039 private ControlMode m_controlMode = ControlMode.PercentOutput; 040 private ControlMode m_sendMode = ControlMode.PercentOutput; 041 042 private InvertType _invert = InvertType.None; 043 044 private boolean _isVcompEn = false; //off by default 045 046 /** 047 * Device handle 048 */ 049 protected long m_handle; 050 051 private int [] _motionProfStats = new int[11]; 052 053 private VictorSPXSimCollection _simCollSpx; 054 055 // --------------------- Constructors -----------------------------// 056 /** 057 * Constructor for motor controllers. 058 * 059 * @param arbId Device ID [0,62] 060 * @param model String specifying device model 061 */ 062 public BaseMotorController(int arbId, String model, String canbus) { 063 m_handle = MotControllerJNI.Create2(arbId, model, canbus); 064 _simCollSpx = new VictorSPXSimCollection(this); 065 } 066 067 /** 068 * Constructor for motor controllers. 069 * 070 * @param arbId Device ID [0,62] 071 * @param model String specifying device model 072 */ 073 public BaseMotorController(int arbId, String model) { 074 this(arbId, model, ""); 075 } 076 077 protected VictorSPXSimCollection getVictorSPXSimCollection() {return _simCollSpx;} 078 079 /** 080 * Destructor for motor controllers 081 * @return Error Code generated by function. 0 indicates no error. 082 */ 083 public ErrorCode DestroyObject() { 084 return ErrorCode.valueOf(MotControllerJNI.JNI_destroy_MotController(m_handle)); 085 } 086 087 //public static void DestroyAllMotControllers() { 088 // MotControllerJNI.JNI_destroy_AllMotControllers(); 089 //} 090 091 /** 092 * @return CCI handle for child classes. 093 */ 094 public long getHandle() { 095 return m_handle; 096 } 097 098 /** 099 * Returns the Device ID 100 * 101 * @return Device number. 102 */ 103 public int getDeviceID() { 104 return MotControllerJNI.GetDeviceNumber(m_handle); 105 } 106 107 // ------ Set output routines. ----------// 108 /** 109 * Sets the appropriate output on the talon, depending on the mode. 110 * @param mode The output mode to apply. 111 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. 112 * In Current mode, output value is in amperes. 113 * In Velocity mode, output value is in position change / 100ms. 114 * In Position mode, output value is in encoder ticks or an analog value, 115 * depending on the sensor. 116 * In Follower mode, the output value is the integer device ID of the talon to 117 * duplicate. 118 * 119 * @param outputValue The setpoint value, as described above. 120 * 121 * 122 * Standard Driving Example: 123 * _talonLeft.set(ControlMode.PercentOutput, leftJoy); 124 * _talonRght.set(ControlMode.PercentOutput, rghtJoy); 125 */ 126 public void set(ControlMode mode, double outputValue) { 127 set(mode, outputValue, DemandType.Neutral, 0); 128 } 129 /** 130 * @param mode Sets the appropriate output on the talon, depending on the mode. 131 * @param demand0 The output value to apply. 132 * such as advanced feed forward and/or auxiliary close-looping in firmware. 133 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. 134 * In Current mode, output value is in amperes. 135 * In Velocity mode, output value is in position change / 100ms. 136 * In Position mode, output value is in encoder ticks or an analog value, 137 * depending on the sensor. See 138 * In Follower mode, the output value is the integer device ID of the talon to 139 * duplicate. 140 * 141 * @param demand1Type The demand type for demand1. 142 * Neutral: Ignore demand1 and apply no change to the demand0 output. 143 * AuxPID: Use demand1 to set the target for the auxiliary PID 1. Auxiliary 144 * PID is always executed as standard Position PID control. 145 * ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the 146 * demand0 output. In PercentOutput the demand0 output is the motor output, 147 * and in closed-loop modes the demand0 output is the output of PID0. 148 * @param demand1 Supplmental output value. 149 * AuxPID: Target position in Sensor Units 150 * ArbitraryFeedForward: Percent Output between -1.0 and 1.0 151 * 152 * 153 * Arcade Drive Example: 154 * _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn); 155 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn); 156 * 157 * Drive Straight Example: 158 * Note: Selected Sensor Configuration is necessary for both PID0 and PID1. 159 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1); 160 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading); 161 * 162 * Drive Straight to a Distance Example: 163 * Note: Other configurations (sensor selection, PID gains, etc.) need to be set. 164 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1); 165 * _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading); 166 */ 167 public void set(ControlMode mode, double demand0, DemandType demand1Type, double demand1){ 168 m_controlMode = mode; 169 m_sendMode = mode; 170 int work; 171 172 switch (m_controlMode) { 173 case PercentOutput: 174 // case TimedPercentOutput: 175 MotControllerJNI.Set_4(m_handle, m_sendMode.value, demand0, demand1, demand1Type.value); 176 break; 177 case Follower: 178 /* did caller specify device ID */ 179 if ((0 <= demand0) && (demand0 <= 62)) { // [0,62] 180 work = getBaseID(); 181 work >>= 16; 182 work <<= 8; 183 work |= ((int) demand0) & 0xFF; 184 } else { 185 work = (int) demand0; 186 } 187 /* single precision guarantees 16bits of integral precision, 188 * so float/double cast on work is safe */ 189 MotControllerJNI.Set_4(m_handle, m_sendMode.value, (double)work, demand1, demand1Type.value); 190 break; 191 case Velocity: 192 case Position: 193 case MotionMagic: 194 case MotionProfile: 195 case MotionProfileArc: 196 MotControllerJNI.Set_4(m_handle, m_sendMode.value, demand0, demand1, demand1Type.value); 197 break; 198 case Current: 199 MotControllerJNI.SetDemand(m_handle, m_sendMode.value, (int) (1000. * demand0), 0); /* milliamps */ 200 break; 201 case MusicTone: 202 MotControllerJNI.Set_4(m_handle, m_sendMode.value, demand0, demand1, demand1Type.value); 203 break; 204 case Disabled: 205 /* fall thru... */ 206 default: 207 MotControllerJNI.SetDemand(m_handle, m_sendMode.value, 0, 0); 208 break; 209 } 210 211 } 212 213 /** 214 * Neutral the motor output by setting control mode to disabled. 215 */ 216 public void neutralOutput() { 217 set(ControlMode.Disabled, 0); 218 } 219 220 /** 221 * Sets the mode of operation during neutral throttle output. 222 * 223 * @param neutralMode 224 * The desired mode of operation when the Controller output 225 * throttle is neutral (ie brake/coast) 226 **/ 227 public void setNeutralMode(NeutralMode neutralMode) { 228 MotControllerJNI.SetNeutralMode(m_handle, neutralMode.value); 229 } 230 231 // ------ Invert behavior ----------// 232 /** 233 * Sets the phase of the sensor. Use when controller forward/reverse output 234 * doesn't correlate to appropriate forward/reverse reading of sensor. 235 * Pick a value so that positive PercentOutput yields a positive change in sensor. 236 * After setting this, user can freely call SetInverted() with any value. 237 * 238 * @param PhaseSensor 239 * Indicates whether to invert the phase of the sensor. 240 */ 241 public void setSensorPhase(boolean PhaseSensor) { 242 MotControllerJNI.SetSensorPhase(m_handle, PhaseSensor); 243 } 244 245 /** 246 * Inverts the hbridge output of the motor controller. 247 * 248 * This does not impact sensor phase and should not be used to correct sensor polarity. 249 * 250 * This will invert the hbridge output but NOT the LEDs. 251 * This ensures.... 252 * - Green LEDs always represents positive request from robot-controller/closed-looping mode. 253 * - Green LEDs correlates to forward limit switch. 254 * - Green LEDs correlates to forward soft limit. 255 * 256 * @param invert 257 * Invert state to set. 258 */ 259 public void setInverted(boolean invert) { 260 if(invert){ 261 setInverted(InvertType.InvertMotorOutput); 262 } 263 else{ 264 setInverted(InvertType.None); 265 } 266 } 267 268 /** 269 * Inverts the hbridge output of the motor controller in relation to the master if present 270 * 271 * This does not impact sensor phase and should not be used to correct sensor polarity. 272 * 273 * This will allow you to either: 274 * - Not invert the motor 275 * - Invert the motor 276 * - Always follow the master regardless of master's inversion 277 * - Always oppose the master regardless of master's inversion 278 * 279 * @param invertType 280 * Invert state to set. 281 */ 282 public void setInverted(InvertType invertType){ 283 _invert = invertType; 284 MotControllerJNI.SetInverted_2(m_handle, invertType.value); 285 } 286 287 /** 288 * @return invert setting of motor output. 289 */ 290 public boolean getInverted() { 291 switch(_invert){ 292 case None:{ 293 return false; 294 } 295 case InvertMotorOutput:{ 296 return true; 297 } 298 default:{ 299 break; 300 } 301 } 302 return MotControllerJNI.GetInverted(m_handle); 303 } 304 305 //----- Factory Default Configuration -----// 306 /** 307 * Revert all configurations to factory default values. 308 * Use this before your individual config* calls to avoid having to config every single param. 309 * 310 * Alternatively you can use the configAllSettings routine. 311 * 312 * @param timeoutMs 313 * Timeout value in ms. Function will generate error if config is 314 * not successful within timeout. 315 * @return Error Code generated by function. 0 indicates no error. 316 */ 317 public ErrorCode configFactoryDefault(int timeoutMs){ 318 int retval = MotControllerJNI.ConfigFactoryDefault(m_handle, timeoutMs); 319 return ErrorCode.valueOf(retval); 320 } 321 /** 322 * Revert all configurations to factory default values. 323 * Use this before your individual config* calls to avoid having to config every single param. 324 * 325 * Alternatively you can use the configAllSettings routine. 326 * 327 * @return Error Code generated by function. 0 indicates no error. 328 */ 329 public ErrorCode configFactoryDefault() { 330 int timeoutMs = 50; 331 int retval = MotControllerJNI.ConfigFactoryDefault(m_handle, timeoutMs); 332 return ErrorCode.valueOf(retval); 333 } 334 335 // ----- general output shaping ------------------// 336 /** 337 * Configures the open-loop ramp rate of throttle output. 338 * 339 * @param secondsFromNeutralToFull 340 * Minimum desired time to go from neutral to full throttle. A 341 * value of '0' will disable the ramp. 342 * @param timeoutMs 343 * Timeout value in ms. If nonzero, function will wait for 344 * config success and report an error if it times out. 345 * If zero, no blocking or checking is performed. 346 * @return Error Code generated by function. 0 indicates no error. 347 */ 348 public ErrorCode configOpenloopRamp(double secondsFromNeutralToFull, int timeoutMs) { 349 int retval = MotControllerJNI.ConfigOpenLoopRamp(m_handle, secondsFromNeutralToFull, timeoutMs); 350 return ErrorCode.valueOf(retval); 351 } 352 /** 353 * Configures the open-loop ramp rate of throttle output. 354 * 355 * @param secondsFromNeutralToFull 356 * Minimum desired time to go from neutral to full throttle. A 357 * value of '0' will disable the ramp. 358 * @return Error Code generated by function. 0 indicates no error. 359 */ 360 public ErrorCode configOpenloopRamp(double secondsFromNeutralToFull) { 361 int timeoutMs = 0; 362 return configOpenloopRamp(secondsFromNeutralToFull, timeoutMs); 363 } 364 365 /** 366 * Configures the closed-loop ramp rate of throttle output. 367 * 368 * @param secondsFromNeutralToFull 369 * Minimum desired time to go from neutral to full throttle. A 370 * value of '0' will disable the ramp. 371 * @param timeoutMs 372 * Timeout value in ms. If nonzero, function will wait for 373 * config success and report an error if it times out. 374 * If zero, no blocking or checking is performed. 375 * @return Error Code generated by function. 0 indicates no error. 376 */ 377 public ErrorCode configClosedloopRamp(double secondsFromNeutralToFull, int timeoutMs) { 378 int retval = MotControllerJNI.ConfigClosedLoopRamp(m_handle, secondsFromNeutralToFull, timeoutMs); 379 return ErrorCode.valueOf(retval); 380 } 381 /** 382 * Configures the closed-loop ramp rate of throttle output. 383 * 384 * @param secondsFromNeutralToFull 385 * Minimum desired time to go from neutral to full throttle. A 386 * value of '0' will disable the ramp. 387 * @return Error Code generated by function. 0 indicates no error. 388 */ 389 public ErrorCode configClosedloopRamp(double secondsFromNeutralToFull) { 390 int timeoutMs = 0; 391 return configClosedloopRamp(secondsFromNeutralToFull, timeoutMs); 392 } 393 394 /** 395 * Configures the forward peak output percentage. 396 * 397 * @param percentOut 398 * Desired peak output percentage. [0,1] 399 * @param timeoutMs 400 * Timeout value in ms. If nonzero, function will wait for 401 * config success and report an error if it times out. 402 * If zero, no blocking or checking is performed. 403 * @return Error Code generated by function. 0 indicates no error. 404 */ 405 public ErrorCode configPeakOutputForward(double percentOut, int timeoutMs) { 406 int retval = MotControllerJNI.ConfigPeakOutputForward(m_handle, percentOut, timeoutMs); 407 return ErrorCode.valueOf(retval); 408 } 409 /** 410 * Configures the forward peak output percentage. 411 * 412 * @param percentOut 413 * Desired peak output percentage. [0,1] 414 * @return Error Code generated by function. 0 indicates no error. 415 */ 416 public ErrorCode configPeakOutputForward(double percentOut) { 417 int timeoutMs = 0; 418 return configPeakOutputForward(percentOut, timeoutMs); 419 } 420 421 /** 422 * Configures the reverse peak output percentage. 423 * 424 * @param percentOut 425 * Desired peak output percentage. 426 * @param timeoutMs 427 * Timeout value in ms. If nonzero, function will wait for 428 * config success and report an error if it times out. 429 * If zero, no blocking or checking is performed. 430 * @return Error Code generated by function. 0 indicates no error. 431 */ 432 public ErrorCode configPeakOutputReverse(double percentOut, int timeoutMs) { 433 int retval = MotControllerJNI.ConfigPeakOutputReverse(m_handle, percentOut, timeoutMs); 434 return ErrorCode.valueOf(retval); 435 } 436 /** 437 * Configures the reverse peak output percentage. 438 * 439 * @param percentOut 440 * Desired peak output percentage. 441 * @return Error Code generated by function. 0 indicates no error. 442 */ 443 public ErrorCode configPeakOutputReverse(double percentOut) { 444 int timeoutMs = 0; 445 return configPeakOutputReverse(percentOut, timeoutMs); 446 } 447 /** 448 * Configures the forward nominal output percentage. 449 * 450 * @param percentOut 451 * Nominal (minimum) percent output. [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 configNominalOutputForward(double percentOut, int timeoutMs) { 459 int retval = MotControllerJNI.ConfigNominalOutputForward(m_handle, percentOut, timeoutMs); 460 return ErrorCode.valueOf(retval); 461 } 462 /** 463 * Configures the forward nominal output percentage. 464 * 465 * @param percentOut 466 * Nominal (minimum) percent output. [0,+1] 467 * @return Error Code generated by function. 0 indicates no error. 468 */ 469 public ErrorCode configNominalOutputForward(double percentOut) { 470 int timeoutMs = 0; 471 return configNominalOutputForward(percentOut, timeoutMs); 472 } 473 474 /** 475 * Configures the reverse nominal output percentage. 476 * 477 * @param percentOut 478 * Nominal (minimum) percent output. [-1,0] 479 * @param timeoutMs 480 * Timeout value in ms. If nonzero, function will wait for 481 * config success and report an error if it times out. 482 * If zero, no blocking or checking is performed. 483 * @return Error Code generated by function. 0 indicates no error. 484 */ 485 public ErrorCode configNominalOutputReverse(double percentOut, int timeoutMs) { 486 int retval = MotControllerJNI.ConfigNominalOutputReverse(m_handle, percentOut, timeoutMs); 487 return ErrorCode.valueOf(retval); 488 } 489 /** 490 * Configures the reverse nominal output percentage. 491 * 492 * @param percentOut 493 * Nominal (minimum) percent output. [-1,0] 494 * @return Error Code generated by function. 0 indicates no error. 495 */ 496 public ErrorCode configNominalOutputReverse(double percentOut) { 497 int timeoutMs = 0; 498 return configNominalOutputReverse(percentOut, timeoutMs); 499 } 500 501 /** 502 * Configures the output deadband percentage. 503 * 504 * @param percentDeadband 505 * Desired deadband percentage. Minimum is 0.1%, Maximum is 25%. 506 * Pass 0.04 for 4% (factory default). 507 * @param timeoutMs 508 * Timeout value in ms. If nonzero, function will wait for 509 * config success and report an error if it times out. 510 * If zero, no blocking or checking is performed. 511 * @return Error Code generated by function. 0 indicates no error. 512 */ 513 public ErrorCode configNeutralDeadband(double percentDeadband, int timeoutMs) { 514 int retval = MotControllerJNI.ConfigNeutralDeadband(m_handle, percentDeadband, timeoutMs); 515 return ErrorCode.valueOf(retval); 516 } 517 /** 518 * Configures the output deadband percentage. 519 * 520 * @param percentDeadband 521 * Desired deadband percentage. Minimum is 0.1%, Maximum is 25%. 522 * Pass 0.04 for 4% (factory default). 523 * @return Error Code generated by function. 0 indicates no error. 524 */ 525 public ErrorCode configNeutralDeadband(double percentDeadband) { 526 int timeoutMs = 0; 527 return configNeutralDeadband(percentDeadband, timeoutMs); 528 } 529 530 // ------ Voltage Compensation ----------// 531 /** 532 * Configures the Voltage Compensation saturation voltage. 533 * 534 * @param voltage 535 * This is the max voltage to apply to the hbridge when voltage 536 * compensation is enabled. For example, if 10 (volts) is specified 537 * and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc) 538 * then the TalonSRX will attempt to apply a duty-cycle to produce 5V. 539 * @param timeoutMs 540 * Timeout value in ms. If nonzero, function will wait for 541 * config success and report an error if it times out. 542 * If zero, no blocking or checking is performed. 543 * @return Error Code generated by function. 0 indicates no error. 544 */ 545 public ErrorCode configVoltageCompSaturation(double voltage, int timeoutMs) { 546 int retval = MotControllerJNI.ConfigVoltageCompSaturation(m_handle, voltage, timeoutMs); 547 return ErrorCode.valueOf(retval); 548 } 549 /** 550 * Configures the Voltage Compensation saturation voltage. 551 * 552 * @param voltage 553 * This is the max voltage to apply to the hbridge when voltage 554 * compensation is enabled. For example, if 10 (volts) is specified 555 * and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc) 556 * then the TalonSRX will attempt to apply a duty-cycle to produce 5V. 557 * @return Error Code generated by function. 0 indicates no error. 558 */ 559 public ErrorCode configVoltageCompSaturation(double voltage) { 560 int timeoutMs = 0; 561 return configVoltageCompSaturation(voltage, timeoutMs); 562 } 563 564 /** 565 * Configures the voltage measurement filter. 566 * 567 * @param filterWindowSamples 568 * Number of samples in the rolling average of voltage 569 * measurement. 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 configVoltageMeasurementFilter(int filterWindowSamples, int timeoutMs) { 577 int retval = MotControllerJNI.ConfigVoltageMeasurementFilter(m_handle, filterWindowSamples, timeoutMs); 578 return ErrorCode.valueOf(retval); 579 } 580 /** 581 * Configures the voltage measurement filter. 582 * 583 * @param filterWindowSamples 584 * Number of samples in the rolling average of voltage 585 * measurement. 586 * @return Error Code generated by function. 0 indicates no error. 587 */ 588 public ErrorCode configVoltageMeasurementFilter(int filterWindowSamples) { 589 int timeoutMs = 0; 590 return configVoltageMeasurementFilter(filterWindowSamples, timeoutMs); 591 } 592 593 /** 594 * Enables voltage compensation. If enabled, voltage compensation works in 595 * all control modes. 596 * 597 * Be sure to configure the saturation voltage before enabling this. 598 * 599 * @param enable 600 * Enable state of voltage compensation. 601 **/ 602 public void enableVoltageCompensation(boolean enable) { 603 _isVcompEn = enable; 604 MotControllerJNI.EnableVoltageCompensation(m_handle, enable); 605 } 606 607 /** 608 * Returns the enable state of Voltage Compensation that the caller has set. 609 * 610 * @return TRUE if voltage compensation is enabled. 611 */ 612 public boolean isVoltageCompensationEnabled(){ 613 return _isVcompEn; 614 } 615 616 // ------ General Status ----------// 617 /** 618 * Gets the bus voltage seen by the device. 619 * 620 * @return The bus voltage value (in volts). 621 */ 622 public double getBusVoltage() { 623 return MotControllerJNI.GetBusVoltage(m_handle); 624 } 625 626 /** 627 * Gets the output percentage of the motor controller. 628 * 629 * @return Output of the motor controller (in percent). 630 */ 631 public double getMotorOutputPercent() { 632 return MotControllerJNI.GetMotorOutputPercent(m_handle); 633 } 634 635 /** 636 * @return applied voltage to motor in volts. 637 */ 638 public double getMotorOutputVoltage() { 639 return getBusVoltage() * getMotorOutputPercent(); 640 } 641 642 /** 643 * Gets the output current of the motor controller. 644 * In the case of TalonSRX class, this routine returns supply current for legacy reasons. In order to get the "true" output current, call GetStatorCurrent(). 645 * 646 * @deprecated Use getStatorCurrent/getSupplyCurrent instead. 647 * 648 * @return The output current (in amps). 649 */ 650 @Deprecated 651 protected double getOutputCurrent() { 652 return MotControllerJNI.GetOutputCurrent(m_handle); 653 } 654 655 /** 656 * Gets the temperature of the motor controller. 657 * 658 * @return Temperature of the motor controller (in 'C) 659 */ 660 public double getTemperature() { 661 return MotControllerJNI.GetTemperature(m_handle); 662 } 663 664 // ------ sensor selection ----------// 665 /** 666 * Select the remote feedback device for the motor controller. 667 * Most CTRE CAN motor controllers will support remote sensors over CAN. 668 * 669 * @param feedbackDevice 670 * Remote Feedback Device to select. 671 * @param pidIdx 672 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 673 * @param timeoutMs 674 * Timeout value in ms. If nonzero, function will wait for 675 * config success and report an error if it times out. 676 * If zero, no blocking or checking is performed. 677 * @return Error Code generated by function. 0 indicates no error. 678 */ 679 public ErrorCode configSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx, int timeoutMs) { 680 int retval = MotControllerJNI.ConfigSelectedFeedbackSensor(m_handle, feedbackDevice.value, pidIdx, timeoutMs); 681 return ErrorCode.valueOf(retval); 682 } 683 /** 684 * Select the remote feedback device for the motor controller. 685 * Most CTRE CAN motor controllers will support remote sensors over CAN. 686 * 687 * @param feedbackDevice 688 * Remote Feedback Device to select. 689 * @return Error Code generated by function. 0 indicates no error. 690 */ 691 public ErrorCode configSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice) { 692 int pidIdx = 0; 693 int timeoutMs = 0; 694 return configSelectedFeedbackSensor(feedbackDevice, pidIdx, timeoutMs); 695 } 696 697 /** 698 * Select the feedback device for the motor controller. 699 * 700 * @param feedbackDevice 701 * Feedback Device to select. 702 * @param pidIdx 703 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 704 * @param timeoutMs 705 * Timeout value in ms. If nonzero, function will wait for 706 * config success and report an error if it times out. 707 * If zero, no blocking or checking is performed. 708 * @return Error Code generated by function. 0 indicates no error. 709 */ 710 public ErrorCode configSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx, int timeoutMs) { 711 int retval = MotControllerJNI.ConfigSelectedFeedbackSensor(m_handle, feedbackDevice.value, pidIdx, timeoutMs); 712 return ErrorCode.valueOf(retval); 713 } 714 /** 715 * Select the feedback device for the motor controller. 716 * 717 * @param feedbackDevice 718 * Feedback Device to select. 719 * @return Error Code generated by function. 0 indicates no error. 720 */ 721 public ErrorCode configSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { 722 int pidIdx = 0; 723 int timeoutMs = 0; 724 return configSelectedFeedbackSensor(feedbackDevice, pidIdx, timeoutMs); 725 } 726 727 /** 728 * The Feedback Coefficient is a scalar applied to the value of the 729 * feedback sensor. Useful when you need to scale your sensor values 730 * within the closed-loop calculations. Default value is 1. 731 * 732 * Selected Feedback Sensor register in firmware is the decoded sensor value 733 * multiplied by the Feedback Coefficient. 734 * 735 * @param coefficient 736 * Feedback Coefficient value. Maximum value of 1. 737 * Resolution is 1/(2^16). Cannot be 0. 738 * @param pidIdx 739 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 740 * @param timeoutMs 741 * Timeout value in ms. If nonzero, function will wait for 742 * config success and report an error if it times out. 743 * If zero, no blocking or checking is performed. 744 * @return Error Code generated by function. 0 indicates no error. 745 */ 746 public ErrorCode configSelectedFeedbackCoefficient(double coefficient, int pidIdx, int timeoutMs) { 747 int retval = MotControllerJNI.ConfigSelectedFeedbackCoefficient(m_handle, coefficient, pidIdx, timeoutMs); 748 return ErrorCode.valueOf(retval); 749 } 750 /** 751 * The Feedback Coefficient is a scalar applied to the value of the 752 * feedback sensor. Useful when you need to scale your sensor values 753 * within the closed-loop calculations. Default value is 1. 754 * 755 * Selected Feedback Sensor register in firmware is the decoded sensor value 756 * multiplied by the Feedback Coefficient. 757 * 758 * @param coefficient 759 * Feedback Coefficient value. Maximum value of 1. 760 * Resolution is 1/(2^16). Cannot be 0. 761 * @return Error Code generated by function. 0 indicates no error. 762 */ 763 public ErrorCode configSelectedFeedbackCoefficient(double coefficient) { 764 int pidIdx = 0; 765 int timeoutMs = 0; 766 return configSelectedFeedbackCoefficient(coefficient, pidIdx, timeoutMs); 767 } 768 /** 769 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. 770 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X 771 * as a PID source for closed-loop features. 772 * 773 * @param deviceID 774 * The device ID of the remote sensor device. 775 * @param remoteSensorSource 776 * The remote sensor device and signal type to bind. 777 * @param remoteOrdinal 778 * 0 for configuring Remote Sensor 0, 779 * 1 for configuring Remote Sensor 1 780 * @param timeoutMs 781 * Timeout value in ms. If nonzero, function will wait for 782 * config success and report an error if it times out. 783 * If zero, no blocking or checking is performed. 784 * @return Error Code generated by function. 0 indicates no error. 785 */ 786 public ErrorCode configRemoteFeedbackFilter(int deviceID, RemoteSensorSource remoteSensorSource, int remoteOrdinal, 787 int timeoutMs) { 788 int retval = MotControllerJNI.ConfigRemoteFeedbackFilter(m_handle, deviceID, remoteSensorSource.value, remoteOrdinal, 789 timeoutMs); 790 return ErrorCode.valueOf(retval); 791 } 792 /** 793 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. 794 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X 795 * as a PID source for closed-loop features. 796 * 797 * @param deviceID 798 * The device ID of the remote sensor device. 799 * @param remoteSensorSource 800 * The remote sensor device and signal type to bind. 801 * @param remoteOrdinal 802 * 0 for configuring Remote Sensor 0, 803 * 1 for configuring Remote Sensor 1 804 * @return Error Code generated by function. 0 indicates no error. 805 */ 806 public ErrorCode configRemoteFeedbackFilter(int deviceID, RemoteSensorSource remoteSensorSource, int remoteOrdinal) { 807 int timeoutMs = 0; 808 return configRemoteFeedbackFilter(deviceID, remoteSensorSource, remoteOrdinal, timeoutMs); 809 } 810 /** 811 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. 812 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X 813 * as a PID source for closed-loop features. 814 * 815 * @param talonRef 816 * Talon device reference to use. 817 * @param remoteOrdinal 818 * 0 for configuring Remote Sensor 0, 819 * 1 for configuring Remote Sensor 1 820 * @param timeoutMs 821 * Timeout value in ms. If nonzero, function will wait for 822 * config success and report an error if it times out. 823 * If zero, no blocking or checking is performed. 824 * @return Error Code generated by function. 0 indicates no error. 825 */ 826 public ErrorCode configRemoteFeedbackFilter(BaseTalon talonRef, int remoteOrdinal, int timeoutMs) { 827 return configRemoteFeedbackFilter(talonRef.getDeviceID(), RemoteSensorSource.TalonSRX_SelectedSensor, remoteOrdinal, timeoutMs); 828 } 829 /** 830 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. 831 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X 832 * as a PID source for closed-loop features. 833 * 834 * @param talonRef 835 * Talon device reference to use. 836 * @param remoteOrdinal 837 * 0 for configuring Remote Sensor 0, 838 * 1 for configuring Remote Sensor 1 839 * @return Error Code generated by function. 0 indicates no error. 840 */ 841 public ErrorCode configRemoteFeedbackFilter(BaseTalon talonRef, int remoteOrdinal) { 842 int timeoutMs = 0; 843 return configRemoteFeedbackFilter(talonRef, remoteOrdinal, timeoutMs); 844 } 845 /** 846 * Select what sensor term should be bound to switch feedback device. 847 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1 848 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1 849 * The four terms are specified with this routine. Then Sensor Sum/Difference 850 * can be selected for closed-looping. 851 * 852 * @param sensorTerm Which sensor term to bind to a feedback source. 853 * @param feedbackDevice The sensor signal to attach to sensorTerm. 854 * @param timeoutMs 855 * Timeout value in ms. If nonzero, function will wait for 856 * config success and report an error if it times out. 857 * If zero, no blocking or checking is performed. 858 * @return Error Code generated by function. 0 indicates no error. 859 */ 860 public ErrorCode configSensorTerm(SensorTerm sensorTerm, FeedbackDevice feedbackDevice, int timeoutMs) { 861 int retval = MotControllerJNI.ConfigSensorTerm(m_handle, sensorTerm.value, feedbackDevice.value, timeoutMs); 862 return ErrorCode.valueOf(retval); 863 } 864 /** 865 * Select what sensor term should be bound to switch feedback device. 866 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1 867 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1 868 * The four terms are specified with this routine. Then Sensor Sum/Difference 869 * can be selected for closed-looping. 870 * 871 * @param sensorTerm Which sensor term to bind to a feedback source. 872 * @param feedbackDevice The sensor signal to attach to sensorTerm. 873 * @return Error Code generated by function. 0 indicates no error. 874 */ 875 public ErrorCode configSensorTerm(SensorTerm sensorTerm, FeedbackDevice feedbackDevice) { 876 int timeoutMs = 0; 877 return configSensorTerm(sensorTerm, feedbackDevice, timeoutMs); 878 } 879 /** 880 * Select what sensor term should be bound to switch feedback device. 881 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1 882 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1 883 * The four terms are specified with this routine. Then Sensor Sum/Difference 884 * can be selected for closed-looping. 885 * 886 * @param sensorTerm Which sensor term to bind to a feedback source. 887 * @param feedbackDevice The sensor signal to attach to sensorTerm. 888 * @param timeoutMs 889 * Timeout value in ms. If nonzero, function will wait for 890 * config success and report an error if it times out. 891 * If zero, no blocking or checking is performed. 892 * @return Error Code generated by function. 0 indicates no error. 893 */ 894 public ErrorCode configSensorTerm(SensorTerm sensorTerm, RemoteFeedbackDevice feedbackDevice, int timeoutMs) { 895 return configSensorTerm(sensorTerm, feedbackDevice.getFeedbackDevice(), timeoutMs); 896 } 897 /** 898 * Select what sensor term should be bound to switch feedback device. 899 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1 900 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1 901 * The four terms are specified with this routine. Then Sensor Sum/Difference 902 * can be selected for closed-looping. 903 * 904 * @param sensorTerm Which sensor term to bind to a feedback source. 905 * @param feedbackDevice The sensor signal to attach to sensorTerm. 906 * @return Error Code generated by function. 0 indicates no error. 907 */ 908 public ErrorCode configSensorTerm(SensorTerm sensorTerm, RemoteFeedbackDevice feedbackDevice) { 909 int timeoutMs = 0; 910 return configSensorTerm(sensorTerm, feedbackDevice.getFeedbackDevice(), timeoutMs); 911 } 912 913 // ------- sensor status --------- // 914 /** 915 * Get the selected sensor position (in raw sensor units). 916 * 917 * @param pidIdx 918 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. See 919 * Phoenix-Documentation for how to interpret. 920 * 921 * @return Position of selected sensor (in raw sensor units). 922 */ 923 public double getSelectedSensorPosition(int pidIdx) { 924 return (double)MotControllerJNI.GetSelectedSensorPosition(m_handle, pidIdx); 925 } 926 /** 927 * Get the selected sensor position (in raw sensor units). 928 * 929 * @return Position of selected sensor (in raw sensor units). 930 */ 931 public double getSelectedSensorPosition() { 932 int pidIdx = 0; 933 return getSelectedSensorPosition(pidIdx); 934 } 935 936 /** 937 * Get the selected sensor velocity. 938 * 939 * @param pidIdx 940 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 941 * @return selected sensor (in raw sensor units) per 100ms. 942 * See Phoenix-Documentation for how to interpret. 943 */ 944 public double getSelectedSensorVelocity(int pidIdx) { 945 return (double)MotControllerJNI.GetSelectedSensorVelocity(m_handle, pidIdx); 946 } 947 /** 948 * Get the selected sensor velocity. 949 * 950 * @return selected sensor (in raw sensor units) per 100ms. 951 * See Phoenix-Documentation for how to interpret. 952 */ 953 public double getSelectedSensorVelocity() { 954 int pidIdx = 0; 955 return getSelectedSensorVelocity(pidIdx); 956 } 957 958 /** 959 * Sets the sensor position to the given value. 960 * 961 * @param sensorPos 962 * Position to set for the selected sensor (in raw sensor units). 963 * @param pidIdx 964 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 965 * @param timeoutMs 966 * Timeout value in ms. If nonzero, function will wait for 967 * config success and report an error if it times out. 968 * If zero, no blocking or checking is performed. 969 * @return Error Code generated by function. 0 indicates no error. 970 */ 971 public ErrorCode setSelectedSensorPosition(double sensorPos, int pidIdx, int timeoutMs) { 972 int retval = MotControllerJNI.SetSelectedSensorPosition(m_handle, (int)sensorPos, pidIdx, timeoutMs); 973 return ErrorCode.valueOf(retval); 974 } 975 /** 976 * Sets the sensor position to the given value. 977 * 978 * @param sensorPos 979 * Position to set for the selected sensor (in raw sensor units). 980 * @return Error Code generated by function. 0 indicates no error. 981 */ 982 public ErrorCode setSelectedSensorPosition(double sensorPos) { 983 int pidIdx = 0; 984 int timeoutMs = 0; 985 return setSelectedSensorPosition(sensorPos, pidIdx, timeoutMs); 986 } 987 988 // ------ status frame period changes ----------// 989 /** 990 * Sets the period of the given control frame. 991 * 992 * @param frame 993 * Frame whose period is to be changed. 994 * @param periodMs 995 * Period in ms for the given frame. 996 * @return Error Code generated by function. 0 indicates no error. 997 */ 998 public ErrorCode setControlFramePeriod(ControlFrame frame, int periodMs) { 999 int retval = MotControllerJNI.SetControlFramePeriod(m_handle, frame.value, periodMs); 1000 return ErrorCode.valueOf(retval); 1001 } 1002 1003 /** 1004 * Sets the period of the given status frame. 1005 * 1006 * User ensure CAN Bus utilization is not high. 1007 * 1008 * This setting is not persistent and is lost when device is reset. 1009 * If this is a concern, calling application can use hasResetOccurred() 1010 * to determine if the status frame needs to be reconfigured. 1011 * 1012 * @param frame 1013 * Frame whose period is to be changed. 1014 * @param periodMs 1015 * Period in ms for the given frame. 1016 * @return Error Code generated by function. 0 indicates no error. 1017 */ 1018 public ErrorCode setControlFramePeriod(int frame, int periodMs) { 1019 int retval = MotControllerJNI.SetControlFramePeriod(m_handle, frame, periodMs); 1020 return ErrorCode.valueOf(retval); 1021 } 1022 1023 /** 1024 * Sets the period of the given status frame. 1025 * 1026 * User ensure CAN Bus utilization is not high. 1027 * 1028 * This setting is not persistent and is lost when device is reset. If this 1029 * is a concern, calling application can use hasResetOccurred() to determine if the 1030 * status frame needs to be reconfigured. 1031 * 1032 * @param frameValue 1033 * Frame whose period is to be changed. 1034 * @param periodMs 1035 * Period in ms for the given frame. 1036 * @param timeoutMs 1037 * Timeout value in ms. If nonzero, function will wait for config 1038 * success and report an error if it times out. If zero, no 1039 * blocking or checking is performed. 1040 * @return Error Code generated by function. 0 indicates no error. 1041 */ 1042 public ErrorCode setStatusFramePeriod(int frameValue, int periodMs, int timeoutMs) { 1043 int retval = MotControllerJNI.SetStatusFramePeriod(m_handle, frameValue, periodMs, timeoutMs); 1044 return ErrorCode.valueOf(retval); 1045 } 1046 /** 1047 * Sets the period of the given status frame. 1048 * 1049 * User ensure CAN Bus utilization is not high. 1050 * 1051 * This setting is not persistent and is lost when device is reset. If this 1052 * is a concern, calling application can use hasResetOccurred() to determine if the 1053 * status frame needs to be reconfigured. 1054 * 1055 * @param frameValue 1056 * Frame whose period is to be changed. 1057 * @param periodMs 1058 * Period in ms for the given frame. 1059 * @return Error Code generated by function. 0 indicates no error. 1060 */ 1061 public ErrorCode setStatusFramePeriod(int frameValue, int periodMs) { 1062 int timeoutMs = 0; 1063 return setStatusFramePeriod(frameValue, periodMs,timeoutMs); 1064 } 1065 1066 /** 1067 * Sets the period of the given status frame. 1068 * 1069 * @param frame 1070 * Frame whose period is to be changed. 1071 * @param periodMs 1072 * Period in ms for the given frame. 1073 * @param timeoutMs 1074 * Timeout value in ms. If nonzero, function will wait for 1075 * config success and report an error if it times out. 1076 * If zero, no blocking or checking is performed. 1077 * @return Error Code generated by function. 0 indicates no error. 1078 */ 1079 public ErrorCode setStatusFramePeriod(StatusFrame frame, int periodMs, int timeoutMs) { 1080 return setStatusFramePeriod(frame.value, periodMs, timeoutMs); 1081 } 1082 /** 1083 * Sets the period of the given status frame. 1084 * 1085 * @param frame 1086 * Frame whose period is to be changed. 1087 * @param periodMs 1088 * Period in ms for the given frame. 1089 * @return Error Code generated by function. 0 indicates no error. 1090 */ 1091 public ErrorCode setStatusFramePeriod(StatusFrame frame, int periodMs) { 1092 int timeoutMs = 0; 1093 return setStatusFramePeriod(frame,periodMs, timeoutMs); 1094 } 1095 1096 /** 1097 * Gets the period of the given status frame. 1098 * 1099 * @param frame 1100 * Frame to get the period of. 1101 * @param timeoutMs 1102 * Timeout value in ms. If nonzero, function will wait for 1103 * config success and report an error if it times out. 1104 * If zero, no blocking or checking is performed. 1105 * @return Period of the given status frame. 1106 */ 1107 public int getStatusFramePeriod(int frame, int timeoutMs) { 1108 return MotControllerJNI.GetStatusFramePeriod(m_handle, frame, timeoutMs); 1109 } 1110 /** 1111 * Gets the period of the given status frame. 1112 * 1113 * @param frame 1114 * Frame to get the period of. 1115 * @return Period of the given status frame. 1116 */ 1117 public int getStatusFramePeriod(int frame) { 1118 int timeoutMs = 0; 1119 return getStatusFramePeriod(frame, timeoutMs); 1120 } 1121 1122 /** 1123 * Gets the period of the given status frame. 1124 * 1125 * @param frame 1126 * Frame to get the period of. 1127 * @param timeoutMs 1128 * Timeout value in ms. If nonzero, function will wait for 1129 * config success and report an error if it times out. 1130 * If zero, no blocking or checking is performed. 1131 * @return Period of the given status frame. 1132 */ 1133 public int getStatusFramePeriod(StatusFrame frame, int timeoutMs) { 1134 return MotControllerJNI.GetStatusFramePeriod(m_handle, frame.value, timeoutMs); 1135 } 1136 /** 1137 * Gets the period of the given status frame. 1138 * 1139 * @param frame 1140 * Frame to get the period of. 1141 * @return Period of the given status frame. 1142 */ 1143 public int getStatusFramePeriod(StatusFrame frame) { 1144 int timeoutMs = 0; 1145 return getStatusFramePeriod(frame, timeoutMs); 1146 } 1147 1148 /** 1149 * Gets the period of the given status frame. 1150 * 1151 * @param frame 1152 * Frame to get the period of. 1153 * @param timeoutMs 1154 * Timeout value in ms. If nonzero, function will wait for 1155 * config success and report an error if it times out. 1156 * If zero, no blocking or checking is performed. 1157 * @return Period of the given status frame. 1158 */ 1159 public int getStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs) { 1160 return MotControllerJNI.GetStatusFramePeriod(m_handle, frame.value, timeoutMs); 1161 } 1162 /** 1163 * Gets the period of the given status frame. 1164 * 1165 * @param frame 1166 * Frame to get the period of. 1167 * @return Period of the given status frame. 1168 */ 1169 public int getStatusFramePeriod(StatusFrameEnhanced frame) { 1170 int timeoutMs = 0; 1171 return getStatusFramePeriod(frame, timeoutMs); 1172 } 1173 1174 // ----- velocity signal conditionaing ------// 1175 1176 /** 1177 * Sets the period over which velocity measurements are taken. 1178 * 1179 * @param period 1180 * Desired period for the velocity measurement. @see 1181 * com.ctre.phoenix.sensors.SensorVelocityMeasPeriod 1182 * @param timeoutMs 1183 * Timeout value in ms. If nonzero, function will wait for 1184 * config success and report an error if it times out. 1185 * If zero, no blocking or checking is performed. 1186 * @return Error Code generated by function. 0 indicates no error. 1187 */ 1188 public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs) { 1189 int retval = MotControllerJNI.ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs); 1190 return ErrorCode.valueOf(retval); 1191 } 1192 /** 1193 * Sets the period over which velocity measurements are taken. 1194 * 1195 * @deprecated Use the overload with SensorVelocityMeasPeriod instead. 1196 * 1197 * @param period 1198 * Desired period for the velocity measurement. @see 1199 * com.ctre.phoenix.motorcontrol.VelocityMeasPeriod 1200 * @param timeoutMs 1201 * Timeout value in ms. If nonzero, function will wait for 1202 * config success and report an error if it times out. 1203 * If zero, no blocking or checking is performed. 1204 * @return Error Code generated by function. 0 indicates no error. 1205 */ 1206 @Deprecated 1207 public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs) { 1208 int retval = MotControllerJNI.ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs); 1209 return ErrorCode.valueOf(retval); 1210 } 1211 /** 1212 * Sets the period over which velocity measurements are taken. 1213 * 1214 * @param period 1215 * Desired period for the velocity measurement. @see 1216 * com.ctre.phoenix.sensors.SensorVelocityMeasPeriod 1217 * @return Error Code generated by function. 0 indicates no error. 1218 */ 1219 public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period) { 1220 int timeoutMs = 0; 1221 return configVelocityMeasurementPeriod(period, timeoutMs); 1222 } 1223 /** 1224 * Sets the period over which velocity measurements are taken. 1225 * 1226 * @deprecated Use the overload with SensorVelocityMeasPeriod instead. 1227 * 1228 * @param period 1229 * Desired period for the velocity measurement. @see 1230 * com.ctre.phoenix.motorcontrol.VelocityMeasPeriod 1231 * @return Error Code generated by function. 0 indicates no error. 1232 */ 1233 @Deprecated 1234 public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period) { 1235 int timeoutMs = 0; 1236 return configVelocityMeasurementPeriod(period, timeoutMs); 1237 } 1238 1239 /** 1240 * Sets the number of velocity samples used in the rolling average velocity 1241 * measurement. 1242 * 1243 * @param windowSize 1244 * Number of samples in the rolling average of velocity 1245 * measurement. Valid values are 1,2,4,8,16,32. If another value 1246 * is specified, it will truncate to nearest support value. 1247 * @param timeoutMs 1248 * Timeout value in ms. If nonzero, function will wait for config 1249 * success and report an error if it times out. If zero, no 1250 * blocking or checking is performed. 1251 * @return Error Code generated by function. 0 indicates no error. 1252 */ 1253 public ErrorCode configVelocityMeasurementWindow(int windowSize, int timeoutMs) { 1254 int retval = MotControllerJNI.ConfigVelocityMeasurementWindow(m_handle, windowSize, timeoutMs); 1255 return ErrorCode.valueOf(retval); 1256 } 1257 /** 1258 * Sets the number of velocity samples used in the rolling average velocity 1259 * measurement. 1260 * 1261 * @param windowSize 1262 * Number of samples in the rolling average of velocity 1263 * measurement. Valid values are 1,2,4,8,16,32. If another value 1264 * is specified, it will truncate to nearest support value. 1265 * @return Error Code generated by function. 0 indicates no error. 1266 */ 1267 public ErrorCode configVelocityMeasurementWindow(int windowSize) { 1268 int timeoutMs = 0; 1269 return configVelocityMeasurementWindow(windowSize, timeoutMs); 1270 } 1271 1272 // ------ remote limit switch ----------// 1273 /** 1274 * Configures the forward limit switch for a remote source. For example, a 1275 * CAN motor controller may need to monitor the Limit-F pin of another Talon 1276 * or CANifier. 1277 * 1278 * @param type 1279 * Remote limit switch source. User can choose between a remote 1280 * Talon SRX, CANifier, or deactivate the feature. 1281 * @param normalOpenOrClose 1282 * Setting for normally open, normally closed, or disabled. This 1283 * setting matches the Phoenix Tuner drop down. 1284 * @param deviceID 1285 * Device ID of remote source (Talon SRX or CANifier device ID). 1286 * @param timeoutMs 1287 * Timeout value in ms. If nonzero, function will wait for config 1288 * success and report an error if it times out. If zero, no 1289 * blocking or checking is performed. 1290 * @return Error Code generated by function. 0 indicates no error. 1291 */ 1292 public ErrorCode configForwardLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, 1293 int deviceID, int timeoutMs) { 1294 return configForwardLimitSwitchSource(type.value, normalOpenOrClose.value, deviceID, timeoutMs); 1295 } 1296 /** 1297 * Configures the forward limit switch for a remote source. For example, a 1298 * CAN motor controller may need to monitor the Limit-F pin of another Talon 1299 * or CANifier. 1300 * 1301 * @param type 1302 * Remote limit switch source. User can choose between a remote 1303 * Talon SRX, CANifier, or deactivate the feature. 1304 * @param normalOpenOrClose 1305 * Setting for normally open, normally closed, or disabled. This 1306 * setting matches the Phoenix Tuner drop down. 1307 * @param deviceID 1308 * Device ID of remote source (Talon SRX or CANifier device ID). 1309 * @return Error Code generated by function. 0 indicates no error. 1310 */ 1311 public ErrorCode configForwardLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, 1312 int deviceID) { 1313 int timeoutMs = 0; 1314 return configForwardLimitSwitchSource(type, normalOpenOrClose, deviceID, timeoutMs); 1315 } 1316 1317 /** 1318 * Configures the reverse limit switch for a remote source. For example, a 1319 * CAN motor controller may need to monitor the Limit-R pin of another Talon 1320 * or CANifier. 1321 * 1322 * @param type 1323 * Remote limit switch source. User can choose between a remote 1324 * Talon SRX, CANifier, or deactivate the feature. 1325 * @param normalOpenOrClose 1326 * Setting for normally open, normally closed, or disabled. This 1327 * setting matches the Phoenix Tuner drop down. 1328 * @param deviceID 1329 * Device ID of remote source (Talon SRX or CANifier device ID). 1330 * @param timeoutMs 1331 * Timeout value in ms. If nonzero, function will wait for config 1332 * success and report an error if it times out. If zero, no 1333 * blocking or checking is performed. 1334 * @return Error Code generated by function. 0 indicates no error. 1335 */ 1336 public ErrorCode configReverseLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, 1337 int deviceID, int timeoutMs) { 1338 int retval = MotControllerJNI.ConfigReverseLimitSwitchSource(m_handle, type.value, normalOpenOrClose.value, 1339 deviceID, timeoutMs); 1340 return ErrorCode.valueOf(retval); 1341 } 1342 /** 1343 * Configures the reverse limit switch for a remote source. For example, a 1344 * CAN motor controller may need to monitor the Limit-R pin of another Talon 1345 * or CANifier. 1346 * 1347 * @param type 1348 * Remote limit switch source. User can choose between a remote 1349 * Talon SRX, CANifier, or deactivate the feature. 1350 * @param normalOpenOrClose 1351 * Setting for normally open, normally closed, or disabled. This 1352 * setting matches the Phoenix Tuner drop down. 1353 * @param deviceID 1354 * Device ID of remote source (Talon SRX or CANifier device ID). 1355 * @return Error Code generated by function. 0 indicates no error. 1356 */ 1357 public ErrorCode configReverseLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, 1358 int deviceID) { 1359 int timeoutMs = 0; 1360 return configReverseLimitSwitchSource(type, normalOpenOrClose, deviceID, timeoutMs); 1361 } 1362 1363 /** 1364 * Configures a limit switch for a local/remote source. 1365 * 1366 * For example, a CAN motor controller may need to monitor the Limit-R pin 1367 * of another Talon, CANifier, or local Gadgeteer feedback connector. 1368 * 1369 * If the sensor is remote, a device ID of zero is assumed. If that's not 1370 * desired, use the four parameter version of this function. 1371 * 1372 * @param type 1373 * Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose 1374 * between the feedback connector, remote Talon SRX, CANifier, or 1375 * deactivate the feature. 1376 * @param normalOpenOrClose 1377 * Setting for normally open, normally closed, or disabled. This 1378 * setting matches the Phoenix Tuner drop down. 1379 * @param timeoutMs 1380 * Timeout value in ms. If nonzero, function will wait for config 1381 * success and report an error if it times out. If zero, no 1382 * blocking or checking is performed. 1383 * @return Error Code generated by function. 0 indicates no error. 1384 */ 1385 public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, 1386 int timeoutMs) { 1387 return configForwardLimitSwitchSource(type.value, normalOpenOrClose.value, -1, timeoutMs); 1388 } 1389 /** 1390 * Configures a limit switch for a local/remote source. 1391 * 1392 * For example, a CAN motor controller may need to monitor the Limit-R pin 1393 * of another Talon, CANifier, or local Gadgeteer feedback connector. 1394 * 1395 * If the sensor is remote, a device ID of zero is assumed. If that's not 1396 * desired, use the four parameter version of this function. 1397 * 1398 * @param type 1399 * Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose 1400 * between the feedback connector, remote Talon SRX, CANifier, or 1401 * deactivate the feature. 1402 * @param normalOpenOrClose 1403 * Setting for normally open, normally closed, or disabled. This 1404 * setting matches the Phoenix Tuner drop down. 1405 * @return Error Code generated by function. 0 indicates no error. 1406 */ 1407 public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose) { 1408 int timeoutMs = 0; 1409 return configForwardLimitSwitchSource(type, normalOpenOrClose, timeoutMs); 1410 } 1411 1412 /** 1413 * Configures a limit switch for a local/remote source. 1414 * 1415 * For example, a CAN motor controller may need to monitor the Limit-R pin 1416 * of another Talon, CANifier, or local Gadgeteer feedback connector. 1417 * 1418 * If the sensor is remote, a device ID of zero is assumed. If that's not 1419 * desired, use the four parameter version of this function. 1420 * 1421 * @param typeValue 1422 * Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose 1423 * between the feedback connector, remote Talon SRX, CANifier, or 1424 * deactivate the feature. 1425 * @param normalOpenOrCloseValue 1426 * Setting for normally open, normally closed, or disabled. This 1427 * setting matches the Phoenix Tuner drop down. 1428 * @param deviceID 1429 * Device ID of remote source (Talon SRX or CANifier device ID). 1430 * @param timeoutMs 1431 * Timeout value in ms. If nonzero, function will wait for config 1432 * success and report an error if it times out. If zero, no 1433 * blocking or checking is performed. 1434 * @return Error Code generated by function. 0 indicates no error. 1435 */ 1436 protected ErrorCode configForwardLimitSwitchSource(int typeValue, int normalOpenOrCloseValue, int deviceID, 1437 int timeoutMs) { 1438 int retval = MotControllerJNI.ConfigForwardLimitSwitchSource(m_handle, typeValue, normalOpenOrCloseValue, 1439 deviceID, timeoutMs); 1440 return ErrorCode.valueOf(retval); 1441 } 1442 1443 /** 1444 * Configures a limit switch for a local/remote source. 1445 * 1446 * For example, a CAN motor controller may need to monitor the Limit-R pin 1447 * of another Talon, CANifier, or local Gadgeteer feedback connector. 1448 * 1449 * If the sensor is remote, a device ID of zero is assumed. If that's not 1450 * desired, use the four parameter version of this function. 1451 * 1452 * @param typeValue 1453 * Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose 1454 * between the feedback connector, remote Talon SRX, CANifier, or 1455 * deactivate the feature. 1456 * @param normalOpenOrCloseValue 1457 * Setting for normally open, normally closed, or disabled. This 1458 * setting matches the Phoenix Tuner drop down. 1459 * @param deviceID 1460 * The device ID of the remote sensor device. 1461 * @param timeoutMs 1462 * Timeout value in ms. If nonzero, function will wait for config 1463 * success and report an error if it times out. If zero, no 1464 * blocking or checking is performed. 1465 * @return Error Code generated by function. 0 indicates no error. 1466 */ 1467 protected ErrorCode configReverseLimitSwitchSource(int typeValue, int normalOpenOrCloseValue, int deviceID, 1468 int timeoutMs) { 1469 int retval = MotControllerJNI.ConfigReverseLimitSwitchSource(m_handle, typeValue, normalOpenOrCloseValue, 1470 deviceID, timeoutMs); 1471 return ErrorCode.valueOf(retval); 1472 } 1473 1474 /** 1475 * Sets the enable state for limit switches. 1476 * 1477 * @param enable 1478 * Enable state for limit switches. 1479 **/ 1480 public void overrideLimitSwitchesEnable(boolean enable) { 1481 MotControllerJNI.OverrideLimitSwitchesEnable(m_handle, enable); 1482 } 1483 1484 // ------ soft limit ----------// 1485 /** 1486 * Configures the forward soft limit threhold. 1487 * 1488 * @param forwardSensorLimit 1489 * Forward Sensor Position Limit (in raw sensor units). 1490 * @param timeoutMs 1491 * Timeout value in ms. If nonzero, function will wait for 1492 * config success and report an error if it times out. 1493 * If zero, no blocking or checking is performed. 1494 * @return Error Code generated by function. 0 indicates no error. 1495 */ 1496 public ErrorCode configForwardSoftLimitThreshold(double forwardSensorLimit, int timeoutMs) { 1497 int retval = MotControllerJNI.ConfigForwardSoftLimitThreshold(m_handle, (int)forwardSensorLimit, timeoutMs); 1498 return ErrorCode.valueOf(retval); 1499 } 1500 /** 1501 * Configures the forward soft limit threhold. 1502 * 1503 * @param forwardSensorLimit 1504 * Forward Sensor Position Limit (in raw sensor units). 1505 * @return Error Code generated by function. 0 indicates no error. 1506 */ 1507 public ErrorCode configForwardSoftLimitThreshold(double forwardSensorLimit) { 1508 int timeoutMs = 0; 1509 return configForwardSoftLimitThreshold(forwardSensorLimit, timeoutMs); 1510 } 1511 1512 /** 1513 * Configures the reverse soft limit threshold. 1514 * 1515 * @param reverseSensorLimit 1516 * Reverse Sensor Position Limit (in raw sensor units). 1517 * @param timeoutMs 1518 * Timeout value in ms. If nonzero, function will wait for 1519 * config success and report an error if it times out. 1520 * If zero, no blocking or checking is performed. 1521 * @return Error Code generated by function. 0 indicates no error. 1522 */ 1523 public ErrorCode configReverseSoftLimitThreshold(double reverseSensorLimit, int timeoutMs) { 1524 int retval = MotControllerJNI.ConfigReverseSoftLimitThreshold(m_handle, (int)reverseSensorLimit, timeoutMs); 1525 return ErrorCode.valueOf(retval); 1526 } 1527 /** 1528 * Configures the reverse soft limit threshold. 1529 * 1530 * @param reverseSensorLimit 1531 * Reverse Sensor Position Limit (in raw sensor units). 1532 * @return Error Code generated by function. 0 indicates no error. 1533 */ 1534 public ErrorCode configReverseSoftLimitThreshold(double reverseSensorLimit) { 1535 int timeoutMs = 0; 1536 return configReverseSoftLimitThreshold(reverseSensorLimit, timeoutMs); 1537 } 1538 1539 /** 1540 * Configures the forward soft limit enable. 1541 * 1542 * @param enable 1543 * Forward Sensor Position Limit Enable. 1544 * @param timeoutMs 1545 * Timeout value in ms. If nonzero, function will wait for 1546 * config success and report an error if it times out. 1547 * If zero, no blocking or checking is performed. 1548 * @return Error Code generated by function. 0 indicates no error. 1549 */ 1550 public ErrorCode configForwardSoftLimitEnable(boolean enable, int timeoutMs) { 1551 int retval = MotControllerJNI.ConfigForwardSoftLimitEnable(m_handle, enable, timeoutMs); 1552 return ErrorCode.valueOf(retval); 1553 } 1554 /** 1555 * Configures the forward soft limit enable. 1556 * 1557 * @param enable 1558 * Forward Sensor Position Limit Enable. 1559 * @return Error Code generated by function. 0 indicates no error. 1560 */ 1561 public ErrorCode configForwardSoftLimitEnable(boolean enable) { 1562 int timeoutMs = 0; 1563 return configForwardSoftLimitEnable(enable, timeoutMs); 1564 } 1565 1566 /** 1567 * Configures the reverse soft limit enable. 1568 * 1569 * @param enable 1570 * Reverse Sensor Position Limit Enable. 1571 * @param timeoutMs 1572 * Timeout value in ms. If nonzero, function will wait for config 1573 * success and report an error if it times out. If zero, no 1574 * blocking or checking is performed. 1575 * @return Error Code generated by function. 0 indicates no error. 1576 */ 1577 public ErrorCode configReverseSoftLimitEnable(boolean enable, int timeoutMs) { 1578 int retval = MotControllerJNI.ConfigReverseSoftLimitEnable(m_handle, enable, timeoutMs); 1579 return ErrorCode.valueOf(retval); 1580 } 1581 /** 1582 * Configures the reverse soft limit enable. 1583 * 1584 * @param enable 1585 * Reverse Sensor Position Limit Enable. 1586 * @return Error Code generated by function. 0 indicates no error. 1587 */ 1588 public ErrorCode configReverseSoftLimitEnable(boolean enable) { 1589 int timeoutMs = 0; 1590 return configReverseSoftLimitEnable(enable, timeoutMs); 1591 } 1592 1593 /** 1594 * Can be used to override-disable the soft limits. 1595 * This function can be used to quickly disable soft limits without 1596 * having to modify the persistent configuration. 1597 * 1598 * @param enable 1599 * Enable state for soft limit switches. 1600 */ 1601 public void overrideSoftLimitsEnable(boolean enable) { 1602 MotControllerJNI.OverrideSoftLimitsEnable(m_handle, enable); 1603 } 1604 1605 // ------ Current Lim ----------// 1606 /* not available in base */ 1607 1608 // ------ General Close loop ----------// 1609 /** 1610 * Sets the 'P' constant in the given parameter slot. 1611 * This is multiplied by closed loop error in sensor units. 1612 * Note the closed loop output interprets a final value of 1023 as full output. 1613 * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation) 1614 * 1615 * @param slotIdx 1616 * Parameter slot for the constant. 1617 * @param value 1618 * Value of the P constant. 1619 * @param timeoutMs 1620 * Timeout value in ms. If nonzero, function will wait for 1621 * config success and report an error if it times out. 1622 * If zero, no blocking or checking is performed. 1623 * @return Error Code generated by function. 0 indicates no error. 1624 */ 1625 public ErrorCode config_kP(int slotIdx, double value, int timeoutMs) { 1626 int retval = MotControllerJNI.Config_kP(m_handle, slotIdx, value, timeoutMs); 1627 return ErrorCode.valueOf(retval); 1628 } 1629 /** 1630 * Sets the 'P' constant in the given parameter slot. 1631 * This is multiplied by closed loop error in sensor units. 1632 * Note the closed loop output interprets a final value of 1023 as full output. 1633 * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation) 1634 * 1635 * @param slotIdx 1636 * Parameter slot for the constant. 1637 * @param value 1638 * Value of the P constant. 1639 * @return Error Code generated by function. 0 indicates no error. 1640 */ 1641 public ErrorCode config_kP(int slotIdx, double value) { 1642 int timeoutMs = 0; 1643 return config_kP( slotIdx, value, timeoutMs); 1644 } 1645 1646 /** 1647 * Sets the 'I' constant in the given parameter slot. 1648 * This is multiplied by accumulated closed loop error in sensor units every PID Loop. 1649 * Note the closed loop output interprets a final value of 1023 as full output. 1650 * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000), 1651 * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds]. 1652 * 1653 * @param slotIdx 1654 * Parameter slot for the constant. 1655 * @param value 1656 * Value of the I constant. 1657 * @param timeoutMs 1658 * Timeout value in ms. If nonzero, function will wait for 1659 * config success and report an error if it times out. 1660 * If zero, no blocking or checking is performed. 1661 * @return Error Code generated by function. 0 indicates no error. 1662 */ 1663 public ErrorCode config_kI(int slotIdx, double value, int timeoutMs) { 1664 int retval = MotControllerJNI.Config_kI(m_handle, slotIdx, value, timeoutMs); 1665 return ErrorCode.valueOf(retval); 1666 } 1667 /** 1668 * Sets the 'I' constant in the given parameter slot. 1669 * This is multiplied by accumulated closed loop error in sensor units every PID Loop. 1670 * Note the closed loop output interprets a final value of 1023 as full output. 1671 * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000), 1672 * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds]. 1673 * 1674 * @param slotIdx 1675 * Parameter slot for the constant. 1676 * @param value 1677 * Value of the I constant. 1678 * @return Error Code generated by function. 0 indicates no error. 1679 */ 1680 public ErrorCode config_kI(int slotIdx, double value) { 1681 int timeoutMs = 0; 1682 1683 return config_kI( slotIdx, value, timeoutMs); 1684 } 1685 1686 /** 1687 * Sets the 'D' constant in the given parameter slot. 1688 * 1689 * This is multiplied by derivative error (sensor units per PID loop, typically 1ms). 1690 * Note the closed loop output interprets a final value of 1023 as full output. 1691 * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec) 1692 * 1693 * @param slotIdx 1694 * Parameter slot for the constant. 1695 * @param value 1696 * Value of the D constant. 1697 * @param timeoutMs 1698 * Timeout value in ms. If nonzero, function will wait for 1699 * config success and report an error if it times out. 1700 * If zero, no blocking or checking is performed. 1701 * @return Error Code generated by function. 0 indicates no error. 1702 */ 1703 public ErrorCode config_kD(int slotIdx, double value, int timeoutMs) { 1704 int retval = MotControllerJNI.Config_kD(m_handle, slotIdx, value, timeoutMs); 1705 return ErrorCode.valueOf(retval); 1706 } 1707 /** 1708 * Sets the 'D' constant in the given parameter slot. 1709 * 1710 * This is multiplied by derivative error (sensor units per PID loop, typically 1ms). 1711 * Note the closed loop output interprets a final value of 1023 as full output. 1712 * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec) 1713 * 1714 * @param slotIdx 1715 * Parameter slot for the constant. 1716 * @param value 1717 * Value of the D constant. 1718 * @return Error Code generated by function. 0 indicates no error. 1719 */ 1720 public ErrorCode config_kD(int slotIdx, double value) { 1721 int timeoutMs = 0; 1722 return config_kD( slotIdx, value, timeoutMs); 1723 } 1724 1725 /** 1726 * Sets the 'F' constant in the given parameter slot. 1727 * 1728 * See documentation for calculation details. 1729 * If using velocity, motion magic, or motion profile, 1730 * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms). 1731 * 1732 * @param slotIdx 1733 * Parameter slot for the constant. 1734 * @param value 1735 * Value of the F constant. 1736 * @param timeoutMs 1737 * Timeout value in ms. If nonzero, function will wait for 1738 * config success and report an error if it times out. 1739 * If zero, no blocking or checking is performed. 1740 * @return Error Code generated by function. 0 indicates no error. 1741 */ 1742 public ErrorCode config_kF(int slotIdx, double value, int timeoutMs) { 1743 int retval = MotControllerJNI.Config_kF(m_handle, slotIdx, value, timeoutMs); 1744 return ErrorCode.valueOf(retval); 1745 } 1746 /** 1747 * Sets the 'F' constant in the given parameter slot. 1748 * 1749 * See documentation for calculation details. 1750 * If using velocity, motion magic, or motion profile, 1751 * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms). 1752 * 1753 * @param slotIdx 1754 * Parameter slot for the constant. 1755 * @param value 1756 * Value of the F constant. 1757 * @return Error Code generated by function. 0 indicates no error. 1758 */ 1759 public ErrorCode config_kF(int slotIdx, double value) { 1760 int timeoutMs = 0; 1761 return config_kF( slotIdx, value, timeoutMs); 1762 } 1763 1764 /** 1765 * Sets the Integral Zone constant in the given parameter slot. If the 1766 * (absolute) closed-loop error is outside of this zone, integral 1767 * accumulator is automatically cleared. This ensures than integral wind up 1768 * events will stop after the sensor gets far enough from its target. 1769 * 1770 * @param slotIdx 1771 * Parameter slot for the constant. 1772 * @param izone 1773 * Value of the Integral Zone constant (closed loop error units X 1774 * 1ms). 1775 * @param timeoutMs 1776 * Timeout value in ms. If nonzero, function will wait for config 1777 * success and report an error if it times out. If zero, no 1778 * blocking or checking is performed. 1779 * @return Error Code generated by function. 0 indicates no error. 1780 */ 1781 public ErrorCode config_IntegralZone(int slotIdx, double izone, int timeoutMs) { 1782 int retval = MotControllerJNI.Config_IntegralZone(m_handle, slotIdx, (int)izone, timeoutMs); 1783 return ErrorCode.valueOf(retval); 1784 } 1785 /** 1786 * Sets the Integral Zone constant in the given parameter slot. If the 1787 * (absolute) closed-loop error is outside of this zone, integral 1788 * accumulator is automatically cleared. This ensures than integral wind up 1789 * events will stop after the sensor gets far enough from its target. 1790 * 1791 * @param slotIdx 1792 * Parameter slot for the constant. 1793 * @param izone 1794 * Value of the Integral Zone constant (closed loop error units X 1795 * 1ms). 1796 * @return Error Code generated by function. 0 indicates no error. 1797 */ 1798 public ErrorCode config_IntegralZone(int slotIdx, double izone) { 1799 int timeoutMs = 0; 1800 return config_IntegralZone( slotIdx, izone, timeoutMs); 1801 } 1802 1803 /** 1804 * Sets the allowable closed-loop error in the given parameter slot. 1805 * 1806 * @param slotIdx 1807 * Parameter slot for the constant. 1808 * @param allowableClosedLoopError 1809 * Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity). 1810 * @param timeoutMs 1811 * Timeout value in ms. If nonzero, function will wait for 1812 * config success and report an error if it times out. 1813 * If zero, no blocking or checking is performed. 1814 * @return Error Code generated by function. 0 indicates no error. 1815 */ 1816 public ErrorCode configAllowableClosedloopError(int slotIdx, double allowableClosedLoopError, int timeoutMs) { 1817 int retval = MotControllerJNI.ConfigAllowableClosedloopError(m_handle, slotIdx, (int)allowableClosedLoopError, 1818 timeoutMs); 1819 return ErrorCode.valueOf(retval); 1820 } 1821 /** 1822 * Sets the allowable closed-loop error in the given parameter slot. 1823 * 1824 * @param slotIdx 1825 * Parameter slot for the constant. 1826 * @param allowableClosedLoopError 1827 * Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity). 1828 * @return Error Code generated by function. 0 indicates no error. 1829 */ 1830 public ErrorCode configAllowableClosedloopError(int slotIdx, double allowableClosedLoopError) { 1831 int timeoutMs = 0; 1832 1833 return configAllowableClosedloopError( slotIdx, allowableClosedLoopError, timeoutMs); 1834 } 1835 1836 /** 1837 * Sets the maximum integral accumulator in the given parameter slot. 1838 * 1839 * @param slotIdx 1840 * Parameter slot for the constant. 1841 * @param iaccum 1842 * Value of the maximum integral accumulator (closed loop error 1843 * units X 1ms). 1844 * @param timeoutMs 1845 * Timeout value in ms. If nonzero, function will wait for config 1846 * success and report an error if it times out. If zero, no 1847 * blocking or checking is performed. 1848 * @return Error Code generated by function. 0 indicates no error. 1849 */ 1850 public ErrorCode configMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs) { 1851 int retval = MotControllerJNI.ConfigMaxIntegralAccumulator(m_handle, slotIdx, iaccum, timeoutMs); 1852 return ErrorCode.valueOf(retval); 1853 } 1854 /** 1855 * Sets the maximum integral accumulator in the given parameter slot. 1856 * 1857 * @param slotIdx 1858 * Parameter slot for the constant. 1859 * @param iaccum 1860 * Value of the maximum integral accumulator (closed loop error 1861 * units X 1ms). 1862 * @return Error Code generated by function. 0 indicates no error. 1863 */ 1864 public ErrorCode configMaxIntegralAccumulator(int slotIdx, double iaccum) { 1865 int timeoutMs = 0; 1866 return configMaxIntegralAccumulator( slotIdx, iaccum, timeoutMs); 1867 } 1868 1869 /** 1870 * Sets the peak closed-loop output. This peak output is slot-specific and 1871 * is applied to the output of the associated PID loop. 1872 * This setting is seperate from the generic Peak Output setting. 1873 * 1874 * @param slotIdx 1875 * Parameter slot for the constant. 1876 * @param percentOut 1877 * Peak Percent Output from 0 to 1. This value is absolute and 1878 * the magnitude will apply in both forward and reverse directions. 1879 * @param timeoutMs 1880 * Timeout value in ms. If nonzero, function will wait for 1881 * config success and report an error if it times out. 1882 * If zero, no blocking or checking is performed. 1883 * @return Error Code generated by function. 0 indicates no error. 1884 */ 1885 public ErrorCode configClosedLoopPeakOutput(int slotIdx, double percentOut, int timeoutMs) { 1886 int retval = MotControllerJNI.ConfigClosedLoopPeakOutput(m_handle, slotIdx, percentOut, timeoutMs); 1887 return ErrorCode.valueOf(retval); 1888 } 1889 /** 1890 * Sets the peak closed-loop output. This peak output is slot-specific and 1891 * is applied to the output of the associated PID loop. 1892 * This setting is seperate from the generic Peak Output setting. 1893 * 1894 * @param slotIdx 1895 * Parameter slot for the constant. 1896 * @param percentOut 1897 * Peak Percent Output from 0 to 1. This value is absolute and 1898 * the magnitude will apply in both forward and reverse directions. 1899 * @return Error Code generated by function. 0 indicates no error. 1900 */ 1901 public ErrorCode configClosedLoopPeakOutput(int slotIdx, double percentOut) { 1902 int timeoutMs = 0; 1903 1904 return configClosedLoopPeakOutput( slotIdx, percentOut, timeoutMs); 1905 } 1906 1907 /** 1908 * Sets the loop time (in milliseconds) of the PID closed-loop calculations. 1909 * Default value is 1 ms. 1910 * 1911 * @param slotIdx 1912 * Parameter slot for the constant. 1913 * @param loopTimeMs 1914 * Loop timing of the closed-loop calculations. Minimum value of 1915 * 1 ms, maximum of 64 ms. 1916 * @param timeoutMs 1917 * Timeout value in ms. If nonzero, function will wait for 1918 * config success and report an error if it times out. 1919 * If zero, no blocking or checking is performed. 1920 * @return Error Code generated by function. 0 indicates no error. 1921 */ 1922 public ErrorCode configClosedLoopPeriod(int slotIdx, int loopTimeMs, int timeoutMs) { 1923 int retval = MotControllerJNI.ConfigClosedLoopPeriod(m_handle, slotIdx, loopTimeMs, timeoutMs); 1924 return ErrorCode.valueOf(retval); 1925 } 1926 /** 1927 * Sets the loop time (in milliseconds) of the PID closed-loop calculations. 1928 * Default value is 1 ms. 1929 * 1930 * @param slotIdx 1931 * Parameter slot for the constant. 1932 * @param loopTimeMs 1933 * Loop timing of the closed-loop calculations. Minimum value of 1934 * 1 ms, maximum of 64 ms. 1935 * @return Error Code generated by function. 0 indicates no error. 1936 */ 1937 public ErrorCode configClosedLoopPeriod(int slotIdx, int loopTimeMs) { 1938 int timeoutMs = 0; 1939 return configClosedLoopPeriod( slotIdx, loopTimeMs, timeoutMs); 1940 } 1941 1942 /** 1943 * Configures the Polarity of the Auxiliary PID (PID1). 1944 * 1945 * Standard Polarity: 1946 * Primary Output = PID0 + PID1, 1947 * Auxiliary Output = PID0 - PID1, 1948 * 1949 * Inverted Polarity: 1950 * Primary Output = PID0 - PID1, 1951 * Auxiliary Output = PID0 + PID1, 1952 * 1953 * @param invert 1954 * If true, use inverted PID1 output polarity. 1955 * @param timeoutMs 1956 * Timeout value in ms. If nonzero, function will wait for config 1957 * success and report an error if it times out. If zero, no 1958 * blocking or checking is performed. 1959 * @return Error Code 1960 */ 1961 public ErrorCode configAuxPIDPolarity(boolean invert, int timeoutMs){ 1962 return configSetParameter(ParamEnum.ePIDLoopPolarity, invert ? 1:0, 0, 1, timeoutMs); 1963 } 1964 /** 1965 * Configures the Polarity of the Auxiliary PID (PID1). 1966 * 1967 * Standard Polarity: 1968 * Primary Output = PID0 + PID1, 1969 * Auxiliary Output = PID0 - PID1, 1970 * 1971 * Inverted Polarity: 1972 * Primary Output = PID0 - PID1, 1973 * Auxiliary Output = PID0 + PID1, 1974 * 1975 * @param invert 1976 * If true, use inverted PID1 output polarity. 1977 * @return Error Code 1978 */ 1979 public ErrorCode configAuxPIDPolarity(boolean invert){ 1980 int timeoutMs = 0; 1981 return configAuxPIDPolarity(invert, timeoutMs); 1982 } 1983 1984 /** 1985 * Sets the integral accumulator. Typically this is used to clear/zero the 1986 * integral accumulator, however some use cases may require seeding the 1987 * accumulator for a faster response. 1988 * 1989 * @param iaccum 1990 * Value to set for the integral accumulator (closed loop error 1991 * units X 1ms). 1992 * @param pidIdx 1993 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 1994 * @param timeoutMs 1995 * Timeout value in ms. If nonzero, function will wait for config 1996 * success and report an error if it times out. If zero, no 1997 * blocking or checking is performed. 1998 * @return Error Code generated by function. 0 indicates no error. 1999 */ 2000 public ErrorCode setIntegralAccumulator(double iaccum, int pidIdx, int timeoutMs) { 2001 int retval = MotControllerJNI.SetIntegralAccumulator(m_handle, iaccum, pidIdx, timeoutMs); 2002 return ErrorCode.valueOf(retval); 2003 } 2004 /** 2005 * Sets the integral accumulator. Typically this is used to clear/zero the 2006 * integral accumulator, however some use cases may require seeding the 2007 * accumulator for a faster response. 2008 * 2009 * @param iaccum 2010 * Value to set for the integral accumulator (closed loop error 2011 * units X 1ms). 2012 * @return Error Code generated by function. 0 indicates no error. 2013 */ 2014 public ErrorCode setIntegralAccumulator(double iaccum) { 2015 int pidIdx = 0; 2016 int timeoutMs = 0; 2017 return setIntegralAccumulator( iaccum, pidIdx, timeoutMs); 2018 } 2019 2020 /** 2021 * Gets the closed-loop error. The units depend on which control mode is in 2022 * use. 2023 * 2024 * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target 2025 * and current sensor value (in sensor units. Example 4096 units per rotation for CTRE Mag Encoder). 2026 * 2027 * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target 2028 * and current sensor value (in sensor units per 100ms). 2029 * 2030 * If using motion profiling or Motion Magic, closed loop error is calculated against the current target, 2031 * and not the "final" target at the end of the profile/movement. 2032 * 2033 * See Phoenix-Documentation information on units. 2034 * 2035 * @param pidIdx 2036 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2037 * @return Closed-loop error value. 2038 */ 2039 public double getClosedLoopError(int pidIdx) { 2040 return (double)MotControllerJNI.GetClosedLoopError(m_handle, pidIdx); 2041 } 2042 /** 2043 * Gets the closed-loop error. The units depend on which control mode is in 2044 * use. 2045 * 2046 * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target 2047 * and current sensor value (in sensor units. Example 4096 units per rotation for CTRE Mag Encoder). 2048 * 2049 * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target 2050 * and current sensor value (in sensor units per 100ms). 2051 * 2052 * If using motion profiling or Motion Magic, closed loop error is calculated against the current target, 2053 * and not the "final" target at the end of the profile/movement. 2054 * 2055 * See Phoenix-Documentation information on units. 2056 * 2057 * @return Closed-loop error value. 2058 */ 2059 public double getClosedLoopError() { 2060 int pidIdx = 0; 2061 return getClosedLoopError( pidIdx); 2062 } 2063 2064 /** 2065 * Gets the iaccum value. 2066 * 2067 * @param pidIdx 2068 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2069 * @return Integral accumulator value (Closed-loop error X 1ms). 2070 */ 2071 public double getIntegralAccumulator(int pidIdx) { 2072 return MotControllerJNI.GetIntegralAccumulator(m_handle, pidIdx); 2073 } 2074 /** 2075 * Gets the iaccum value. 2076 * 2077 * @return Integral accumulator value (Closed-loop error X 1ms). 2078 */ 2079 public double getIntegralAccumulator() { 2080 int pidIdx = 0; 2081 return getIntegralAccumulator(pidIdx); 2082 } 2083 2084 2085 /** 2086 * Gets the derivative of the closed-loop error. 2087 * 2088 * @param pidIdx 2089 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2090 * @return The error derivative value. 2091 */ 2092 public double getErrorDerivative(int pidIdx) { 2093 return MotControllerJNI.GetErrorDerivative(m_handle, pidIdx); 2094 } 2095 /** 2096 * Gets the derivative of the closed-loop error. 2097 * 2098 * @return The error derivative value. 2099 */ 2100 public double getErrorDerivative() { 2101 int pidIdx = 0; 2102 2103 return getErrorDerivative(pidIdx); 2104 } 2105 2106 /** 2107 * Selects which profile slot to use for closed-loop control. 2108 * 2109 * @param slotIdx 2110 * Profile slot to select. 2111 * @param pidIdx 2112 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2113 **/ 2114 public void selectProfileSlot(int slotIdx, int pidIdx) { 2115 MotControllerJNI.SelectProfileSlot(m_handle, slotIdx, pidIdx); 2116 } 2117 2118 /** 2119 * Gets the current target of a given closed loop. 2120 * 2121 * @param pidIdx 2122 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2123 * @return The closed loop target. 2124 */ 2125 public double getClosedLoopTarget(int pidIdx) { 2126 double value = MotControllerJNI.GetClosedLoopTarget(m_handle, pidIdx); 2127 if(m_controlMode == ControlMode.Current){ 2128 value = value / 1000; //convert back to amps 2129 } 2130 return value; 2131 } 2132 /** 2133 * Gets the current target of a given closed loop. 2134 * 2135 * @return The closed loop target. 2136 */ 2137 public double getClosedLoopTarget() { 2138 int pidIdx = 0; 2139 return getClosedLoopTarget(pidIdx); 2140 } 2141 2142 /** 2143 * Gets the active trajectory target position for pid0 using 2144 * MotionMagic/MotionProfile control modes. 2145 * 2146 * @return The Active Trajectory Position in sensor units. 2147 */ 2148 public double getActiveTrajectoryPosition() { 2149 return (double)MotControllerJNI.GetActiveTrajectoryPosition(m_handle); 2150 } 2151 2152 /** 2153 * Gets the active trajectory target position using 2154 * MotionMagic/MotionProfile control modes. 2155 * 2156 * @param pidIdx 2157 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2158 * @return The Active Trajectory Position in sensor units. 2159 */ 2160 public double getActiveTrajectoryPosition(int pidIdx) { 2161 return (double)MotControllerJNI.GetActiveTrajectoryPosition3(m_handle, pidIdx); 2162 } 2163 2164 /** 2165 * Gets the active trajectory target velocity for pid0 using 2166 * MotionMagic/MotionProfile control modes. 2167 * 2168 * @return The Active Trajectory Velocity in sensor units per 100ms. 2169 */ 2170 public double getActiveTrajectoryVelocity() { 2171 return (double)MotControllerJNI.GetActiveTrajectoryVelocity(m_handle); 2172 } 2173 2174 /** 2175 * Gets the active trajectory target velocity using 2176 * MotionMagic/MotionProfile control modes. 2177 * 2178 * @param pidIdx 2179 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2180 * @return The Active Trajectory Velocity in sensor units per 100ms. 2181 */ 2182 public double getActiveTrajectoryVelocity(int pidIdx) { 2183 return (double)MotControllerJNI.GetActiveTrajectoryVelocity3(m_handle, pidIdx); 2184 } 2185 2186 /** 2187 * Gets the active trajectory arbitrary feedforward for pid0 using 2188 * MotionMagic/MotionProfile control modes. 2189 * 2190 * @return The Active Trajectory ArbFeedFwd in units of percent output 2191 * (where 0.01 is 1%). 2192 */ 2193 public double getActiveTrajectoryArbFeedFwd() { 2194 return MotControllerJNI.GetActiveTrajectoryArbFeedFwd3(m_handle, 0); 2195 } 2196 2197 /** 2198 * Gets the active trajectory arbitrary feedforward using 2199 * MotionMagic/MotionProfile control modes. 2200 * 2201 * @param pidIdx 2202 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. 2203 * @return The Active Trajectory ArbFeedFwd in units of percent output 2204 * (where 0.01 is 1%). 2205 */ 2206 public double getActiveTrajectoryArbFeedFwd(int pidIdx) { 2207 return MotControllerJNI.GetActiveTrajectoryArbFeedFwd3(m_handle, pidIdx); 2208 } 2209 2210 // ------ Motion Profile Settings used in Motion Magic and Motion Profile ----------// 2211 2212 /** 2213 * Sets the Motion Magic Cruise Velocity. This is the peak target velocity 2214 * that the motion magic curve generator can use. 2215 * 2216 * @param sensorUnitsPer100ms 2217 * Motion Magic Cruise Velocity (in raw sensor units per 100 ms). 2218 * @param timeoutMs 2219 * Timeout value in ms. If nonzero, function will wait for config 2220 * success and report an error if it times out. If zero, no 2221 * blocking or checking is performed. 2222 * @return Error Code generated by function. 0 indicates no error. 2223 */ 2224 public ErrorCode configMotionCruiseVelocity(double sensorUnitsPer100ms, int timeoutMs) { 2225 int retval = MotControllerJNI.ConfigMotionCruiseVelocity(m_handle, (int)sensorUnitsPer100ms, timeoutMs); 2226 return ErrorCode.valueOf(retval); 2227 } 2228 /** 2229 * Sets the Motion Magic Cruise Velocity. This is the peak target velocity 2230 * that the motion magic curve generator can use. 2231 * 2232 * @param sensorUnitsPer100ms 2233 * Motion Magic Cruise Velocity (in raw sensor units per 100 ms). 2234 * @return Error Code generated by function. 0 indicates no error. 2235 */ 2236 public ErrorCode configMotionCruiseVelocity(double sensorUnitsPer100ms) { 2237 int timeoutMs = 0; 2238 return configMotionCruiseVelocity( sensorUnitsPer100ms, timeoutMs); 2239 } 2240 2241 /** 2242 * Sets the Motion Magic Acceleration. This is the target acceleration that 2243 * the motion magic curve generator can use. 2244 * 2245 * @param sensorUnitsPer100msPerSec 2246 * Motion Magic Acceleration (in raw sensor units per 100 ms per 2247 * second). 2248 * @param timeoutMs 2249 * Timeout value in ms. If nonzero, function will wait for config 2250 * success and report an error if it times out. If zero, no 2251 * blocking or checking is performed. 2252 * @return Error Code generated by function. 0 indicates no error. 2253 */ 2254 public ErrorCode configMotionAcceleration(double sensorUnitsPer100msPerSec, int timeoutMs) { 2255 int retval = MotControllerJNI.ConfigMotionAcceleration(m_handle, (int)sensorUnitsPer100msPerSec, timeoutMs); 2256 return ErrorCode.valueOf(retval); 2257 } 2258 /** 2259 * Sets the Motion Magic Acceleration. This is the target acceleration that 2260 * the motion magic curve generator can use. 2261 * 2262 * @param sensorUnitsPer100msPerSec 2263 * Motion Magic Acceleration (in raw sensor units per 100 ms per 2264 * second). 2265 * @return Error Code generated by function. 0 indicates no error. 2266 */ 2267 public ErrorCode configMotionAcceleration(double sensorUnitsPer100msPerSec) { 2268 int timeoutMs = 0; 2269 return configMotionAcceleration( sensorUnitsPer100msPerSec, timeoutMs); 2270 } 2271 2272 /** 2273 * Sets the Motion Magic S Curve Strength. 2274 * Call this before using Motion Magic. 2275 * Modifying this during a Motion Magic action should be avoided. 2276 * 2277 * @param curveStrength 2278 * 0 to use Trapezoidal Motion Profile. [1,8] for S-Curve (greater value yields greater smoothing). 2279 * @param timeoutMs 2280 * Timeout value in ms. If nonzero, function will wait for config 2281 * success and report an error if it times out. If zero, no 2282 * blocking or checking is performed. 2283 * @return Error Code generated by function. 0 indicates no error. 2284 */ 2285 public ErrorCode configMotionSCurveStrength(int curveStrength, int timeoutMs) { 2286 int retval = MotControllerJNI.ConfigMotionSCurveStrength(m_handle, curveStrength, timeoutMs); 2287 return ErrorCode.valueOf(retval); 2288 } 2289 2290 /** 2291 * Sets the Motion Magic S Curve Strength. 2292 * Call this before using Motion Magic. 2293 * Modifying this during a Motion Magic action should be avoided. 2294 * 2295 * @param curveStrength 2296 * 0 to use Trapezoidal Motion Profile. [1,8] for S-Curve (greater value yields greater smoothing). 2297 * @return Error Code generated by function. 0 indicates no error. 2298 */ 2299 public ErrorCode configMotionSCurveStrength(int curveStrength) { 2300 int timeoutMs = 0; 2301 return configMotionSCurveStrength(curveStrength, timeoutMs); 2302 } 2303 2304 //------ Motion Profile Buffer ----------// 2305 /** 2306 * Clear the buffered motion profile in both controller's RAM (bottom), and in the 2307 * API (top). 2308 * @return Error Code generated by function. 0 indicates no error. 2309 */ 2310 public ErrorCode clearMotionProfileTrajectories() { 2311 int retval = MotControllerJNI.ClearMotionProfileTrajectories(m_handle); 2312 return ErrorCode.valueOf(retval); 2313 } 2314 2315 /** 2316 * Retrieve just the buffer count for the api-level (top) buffer. This 2317 * routine performs no CAN or data structure lookups, so its fast and ideal 2318 * if caller needs to quickly poll the progress of trajectory points being 2319 * emptied into controller's RAM. Otherwise just use GetMotionProfileStatus. 2320 * 2321 * @return number of trajectory points in the top buffer. 2322 */ 2323 public int getMotionProfileTopLevelBufferCount() { 2324 return MotControllerJNI.GetMotionProfileTopLevelBufferCount(m_handle); 2325 } 2326 /** 2327 * Push another trajectory point into the top level buffer (which is emptied 2328 * into the motor controller's bottom buffer as room allows). 2329 * @param trajPt to push into buffer. 2330 * The members should be filled in with these values... 2331 * 2332 * targPos: servo position in sensor units. 2333 * targVel: velocity to feed-forward in sensor units 2334 * per 100ms. 2335 * profileSlotSelect0 Which slot to get PIDF gains. PID is used for position servo. F is used 2336 * as the Kv constant for velocity feed-forward. Typically this is hardcoded 2337 * to the a particular slot, but you are free gain schedule if need be. 2338 * Choose from [0,3] 2339 * profileSlotSelect1 Which slot to get PIDF gains for auxiliary PId. 2340 * This only has impact during MotionProfileArc Control mode. 2341 * Choose from [0,1]. 2342 * isLastPoint set to nonzero to signal motor controller to keep processing this 2343 * trajectory point, instead of jumping to the next one 2344 * when timeDurMs expires. Otherwise MP executer will 2345 * eventually see an empty buffer after the last point 2346 * expires, causing it to assert the IsUnderRun flag. 2347 * However this may be desired if calling application 2348 * never wants to terminate the MP. 2349 * zeroPos set to nonzero to signal motor controller to "zero" the selected 2350 * position sensor before executing this trajectory point. 2351 * Typically the first point should have this set only thus 2352 * allowing the remainder of the MP positions to be relative to 2353 * zero. 2354 * timeDur Duration to apply this trajectory pt. 2355 * This time unit is ADDED to the exising base time set by 2356 * configMotionProfileTrajectoryPeriod(). 2357 * @return CTR_OKAY if trajectory point push ok. ErrorCode if buffer is 2358 * full due to kMotionProfileTopBufferCapacity. 2359 */ 2360 public ErrorCode pushMotionProfileTrajectory(TrajectoryPoint trajPt) { 2361 int retval = MotControllerJNI.PushMotionProfileTrajectory3(m_handle, trajPt.position, trajPt.velocity, trajPt.arbFeedFwd, trajPt.auxiliaryPos, trajPt.auxiliaryVel, trajPt.auxiliaryArbFeedFwd, trajPt.profileSlotSelect0, trajPt.profileSlotSelect1, trajPt.isLastPoint, trajPt.zeroPos, trajPt.timeDur, trajPt.useAuxPID); 2362 return ErrorCode.valueOf(retval); 2363 } 2364 2365 /** 2366 * Simple one-shot firing of a complete MP. 2367 * Starting in 2019, MPs can be fired by building a Buffered Trajectory Point Stream, and calling this routine. 2368 * 2369 * Once called, the motor controller software will automatically ... 2370 * [1] Clear the firmware buffer of trajectory points. 2371 * [2] Clear the underrun flags 2372 * [3] Reset an index within the Buffered Trajectory Point Stream (so that the same profile can be run again and again). 2373 * [4] Start a background thread to manage MP streaming (if not already running). 2374 * [5a] If current control mode already matches motionProfControlMode, set MPE Output to "Hold". 2375 * [5b] If current control mode does not matches motionProfControlMode, apply motionProfControlMode and set MPE Output to "Disable". 2376 * [6] Stream the trajectory points into the device's firmware buffer. 2377 * [7] Once motor controller has at least minBufferedPts worth in the firmware buffer, MP will automatically start (MPE Output set to "Enable"). 2378 * [8] Wait until MP finishes, then transitions the Motion Profile Executor's output to "Hold". 2379 * [9] IsMotionProfileFinished() will now return true. 2380 * 2381 * Calling application can use IsMotionProfileFinished() to determine when internal state machine reaches [7]. 2382 * Calling application can cancel MP by calling set(). Otherwise do not call set() until MP has completed. 2383 * 2384 * The legacy API from previous years requires the calling application to pass points via the ProcessMotionProfileBuffer and PushMotionProfileTrajectory. 2385 * This is no longer required if using this StartMotionProfile/IsMotionProfileFinished API. 2386 * 2387 * @param stream A buffer that will be used to stream the trajectory points. Caller can fill this container with the entire trajectory point, regardless of size. 2388 * @param minBufferedPts Minimum number of firmware buffered points before starting MP. 2389 * Do not exceed device's firmware buffer capacity or MP will never fire (120 for Motion Profile, or 60 for Motion Profile Arc). 2390 * Recommendation value for this would be five to ten samples depending on timeDur of the trajectory point. 2391 * @param motionProfControlMode Pass MotionProfile or MotionProfileArc. 2392 * @return nonzero error code if operation fails. 2393 */ 2394 public ErrorCode startMotionProfile(BufferedTrajectoryPointStream stream, int minBufferedPts, ControlMode motionProfControlMode) { 2395 int retval = MotControllerJNI.StartMotionProfile(m_handle, stream.getHandle(), minBufferedPts, motionProfControlMode.value); 2396 return ErrorCode.valueOf(retval); 2397 } 2398 /** 2399 * Determine if running MP is complete. 2400 * This requires using the StartMotionProfile routine to start the MP. 2401 * That is because managing the trajectory points is now done in a background thread (if StartMotionProfile is called). 2402 * 2403 * If calling application uses the legacy API (more-complex buffering API) from previous years, than this API will 2404 * not return true. 2405 * 2406 * @return true if MP was started using StartMotionProfile, and it has completed execution (MPE is now in "hold"). 2407 */ 2408 public boolean isMotionProfileFinished() { 2409 return MotControllerJNI.IsMotionProfileFinished(m_handle); 2410 } 2411 2412 /** 2413 * Retrieve just the buffer full for the api-level (top) buffer. This 2414 * routine performs no CAN or data structure lookups, so its fast and ideal 2415 * if caller needs to quickly poll. Otherwise just use 2416 * GetMotionProfileStatus. 2417 * 2418 * @return number of trajectory points in the top buffer. 2419 */ 2420 public boolean isMotionProfileTopLevelBufferFull() { 2421 return MotControllerJNI.IsMotionProfileTopLevelBufferFull(m_handle); 2422 } 2423 2424 /** 2425 * This must be called periodically to funnel the trajectory points from the 2426 * API's top level buffer to the controller's bottom level buffer. Recommendation 2427 * is to call this twice as fast as the execution rate of the motion 2428 * profile. So if MP is running with 20ms trajectory points, try calling 2429 * this routine every 10ms. All motion profile functions are thread-safe 2430 * through the use of a mutex, so there is no harm in having the caller 2431 * utilize threading. 2432 */ 2433 public void processMotionProfileBuffer() { 2434 MotControllerJNI.ProcessMotionProfileBuffer(m_handle); 2435 } 2436 /** 2437 * Retrieve all status information. 2438 * For best performance, Caller can snapshot all status information regarding the 2439 * motion profile executer. 2440 * 2441 * @param statusToFill Caller supplied object to fill. 2442 * 2443 * The members are filled, as follows... 2444 * 2445 * topBufferRem: The available empty slots in the trajectory buffer. 2446 * The robot API holds a "top buffer" of trajectory points, so your applicaion 2447 * can dump several points at once. The API will then stream them into the 2448 * low-level buffer, allowing the motor controller to act on them. 2449 * 2450 * topBufferRem: The number of points in the top trajectory buffer. 2451 * 2452 * btmBufferCnt: The number of points in the low level controller buffer. 2453 * 2454 * hasUnderrun: Set if isUnderrun ever gets set. 2455 * Can be manually cleared by clearMotionProfileHasUnderrun() or automatically cleared by startMotionProfile(). 2456 * 2457 * isUnderrun: This is set if controller needs to shift a point from its buffer into 2458 * the active trajectory point however 2459 * the buffer is empty. 2460 * This gets cleared automatically when is resolved. 2461 * 2462 * activePointValid: True if the active trajectory point is not empty, false otherwise. The members in activePoint are only valid if this signal is set. 2463 * 2464 * isLast: is set/cleared based on the MP executer's current 2465 * trajectory point's IsLast value. This assumes 2466 * IsLast was set when PushMotionProfileTrajectory 2467 * was used to insert the currently processed trajectory 2468 * point. 2469 * 2470 * profileSlotSelect: The currently processed trajectory point's 2471 * selected slot. This can differ in the currently selected slot used 2472 * for Position and Velocity servo modes 2473 * 2474 * outputEnable: The current output mode of the motion profile 2475 * executer (disabled, enabled, or hold). When changing the set() 2476 * value in MP mode, it's important to check this signal to 2477 * confirm the change takes effect before interacting with the top buffer. 2478 * 2479 * @return Error Code generated by function. 0 indicates no error. 2480 */ 2481 public ErrorCode getMotionProfileStatus(MotionProfileStatus statusToFill) { 2482 int retval = MotControllerJNI.GetMotionProfileStatus2(m_handle, _motionProfStats); 2483 statusToFill.topBufferRem = _motionProfStats[0]; 2484 statusToFill.topBufferCnt = _motionProfStats[1]; 2485 statusToFill.btmBufferCnt = _motionProfStats[2]; 2486 statusToFill.hasUnderrun = _motionProfStats[3] != 0; 2487 statusToFill.isUnderrun = _motionProfStats[4] != 0; 2488 statusToFill.activePointValid = _motionProfStats[5] != 0; 2489 statusToFill.isLast = _motionProfStats[6] != 0; 2490 statusToFill.profileSlotSelect = _motionProfStats[7]; 2491 statusToFill.outputEnable = SetValueMotionProfile.valueOf(_motionProfStats[8]); 2492 statusToFill.timeDurMs = _motionProfStats[9]; 2493 statusToFill.profileSlotSelect1 = _motionProfStats[10]; 2494 return ErrorCode.valueOf(retval); 2495 } 2496 2497 /** 2498 * Clear the "Has Underrun" flag. Typically this is called after application 2499 * has confirmed an underrun had occured. 2500 * 2501 * @param timeoutMs 2502 * Timeout value in ms. If nonzero, function will wait for config 2503 * success and report an error if it times out. If zero, no 2504 * blocking or checking is performed. 2505 * @return Error Code generated by function. 0 indicates no error. 2506 */ 2507 public ErrorCode clearMotionProfileHasUnderrun(int timeoutMs) { 2508 int retval = MotControllerJNI.ClearMotionProfileHasUnderrun(m_handle, timeoutMs); 2509 return ErrorCode.valueOf(retval); 2510 } 2511 /** 2512 * Clear the "Has Underrun" flag. Typically this is called after application 2513 * has confirmed an underrun had occured. 2514 * 2515 * @return Error Code generated by function. 0 indicates no error. 2516 */ 2517 public ErrorCode clearMotionProfileHasUnderrun() { 2518 int timeoutMs = 0; 2519 return clearMotionProfileHasUnderrun(timeoutMs); 2520 } 2521 2522 /** 2523 * Calling application can opt to speed up the handshaking between the robot 2524 * API and the controller to increase the download rate of the controller's Motion 2525 * Profile. Ideally the period should be no more than half the period of a 2526 * trajectory point. 2527 * 2528 * @param periodMs 2529 * The transmit period in ms. 2530 * @return Error Code generated by function. 0 indicates no error. 2531 */ 2532 public ErrorCode changeMotionControlFramePeriod(int periodMs) { 2533 int retval = MotControllerJNI.ChangeMotionControlFramePeriod(m_handle, periodMs); 2534 return ErrorCode.valueOf(retval); 2535 } 2536 2537 /** 2538 * When trajectory points are processed in the motion profile executer, the MPE determines 2539 * how long to apply the active trajectory point by summing baseTrajDurationMs with the 2540 * timeDur of the trajectory point (see TrajectoryPoint). 2541 * 2542 * This allows general selection of the execution rate of the points with 1ms resolution, 2543 * while allowing some degree of change from point to point. 2544 * @param baseTrajDurationMs The base duration time of every trajectory point. 2545 * This is summed with the trajectory points unique timeDur. 2546 * @param timeoutMs 2547 * Timeout value in ms. If nonzero, function will wait for 2548 * config success and report an error if it times out. 2549 * If zero, no blocking or checking is performed. 2550 * @return Error Code generated by function. 0 indicates no error. 2551 */ 2552 public ErrorCode configMotionProfileTrajectoryPeriod(int baseTrajDurationMs, int timeoutMs) { 2553 int retval = MotControllerJNI.ConfigMotionProfileTrajectoryPeriod(m_handle, baseTrajDurationMs, timeoutMs); 2554 return ErrorCode.valueOf(retval); 2555 } 2556 /** 2557 * When trajectory points are processed in the motion profile executer, the MPE determines 2558 * how long to apply the active trajectory point by summing baseTrajDurationMs with the 2559 * timeDur of the trajectory point (see TrajectoryPoint). 2560 * 2561 * This allows general selection of the execution rate of the points with 1ms resolution, 2562 * while allowing some degree of change from point to point. 2563 * @param baseTrajDurationMs The base duration time of every trajectory point. 2564 * This is summed with the trajectory points unique timeDur. 2565 * @return Error Code generated by function. 0 indicates no error. 2566 */ 2567 public ErrorCode configMotionProfileTrajectoryPeriod(int baseTrajDurationMs) { 2568 int timeoutMs = 0; 2569 return configMotionProfileTrajectoryPeriod( baseTrajDurationMs, timeoutMs); 2570 } 2571 2572 /** 2573 * When trajectory points are processed in the buffer, the motor controller can 2574 * linearly interpolate additional trajectory points between the buffered 2575 * points. The time delta between these interpolated points is 1 ms. 2576 * 2577 * By default this feature is enabled. 2578 * 2579 * @param enable Whether to enable the trajectory point interpolation feature. 2580 * @param timeoutMs 2581 * Timeout value in ms. If nonzero, function will wait for 2582 * config success and report an error if it times out. 2583 * If zero, no blocking or checking is performed. 2584 * @return Error Code generated by function. 0 indicates no error. 2585 */ 2586 public ErrorCode configMotionProfileTrajectoryInterpolationEnable(boolean enable, int timeoutMs) { 2587 int retval = MotControllerJNI.ConfigMotionProfileTrajectoryInterpolationEnable(m_handle, enable, timeoutMs); 2588 return ErrorCode.valueOf(retval); 2589 } 2590 /** 2591 * When trajectory points are processed in the buffer, the motor controller can 2592 * linearly interpolate additional trajectory points between the buffered 2593 * points. The time delta between these interpolated points is 1 ms. 2594 * 2595 * By default this feature is enabled. 2596 * 2597 * @param enable Whether to enable the trajectory point interpolation feature. 2598 * @return Error Code generated by function. 0 indicates no error. 2599 */ 2600 public ErrorCode configMotionProfileTrajectoryInterpolationEnable(boolean enable) { 2601 int timeoutMs = 0; 2602 return configMotionProfileTrajectoryInterpolationEnable(enable, timeoutMs); 2603 } 2604 2605 //------Feedback Device Interaction Settings---------// 2606 2607 /** 2608 * Disables continuous tracking of the position for analog and pulse-width. 2609 * If the signal goes from 4095 to 0 (pulse-width) a motor controller will continue to read 4096 by default. 2610 * If overflow tracking is disabled, it will wrap to 0 (not continuous) 2611 * 2612 * If using pulse-width on CTRE Mag Encoder (within one rotation) or absolute analog sensor (within one rotation), 2613 * setting feedbackNotContinuous to true is recommended, to prevent intermittent 2614 * connections from causing sensor "jumps" of 4096 (or 1024 for analog) units. 2615 * 2616 * @param feedbackNotContinuous True to disable the overflow tracking. 2617 * 2618 * @param timeoutMs 2619 * Timeout value in ms. If nonzero, function will wait for 2620 * config success and report an error if it times out. 2621 * If zero, no blocking or checking is performed. 2622 * @return Error Code generated by function. 0 indicates no error. 2623 */ 2624 public ErrorCode configFeedbackNotContinuous(boolean feedbackNotContinuous, int timeoutMs) { 2625 int retval = MotControllerJNI.ConfigFeedbackNotContinuous(m_handle, feedbackNotContinuous, timeoutMs); 2626 return ErrorCode.valueOf(retval); 2627 } 2628 2629 /** 2630 * Disables going to neutral (brake/coast) when a remote sensor is no longer detected. 2631 * 2632 * @param remoteSensorClosedLoopDisableNeutralOnLOS disable going to neutral 2633 * 2634 * @param timeoutMs 2635 * Timeout value in ms. If nonzero, function will wait for 2636 * config success and report an error if it times out. 2637 * If zero, no blocking or checking is performed. 2638 * @return Error Code generated by function. 0 indicates no error. 2639 */ 2640 public ErrorCode configRemoteSensorClosedLoopDisableNeutralOnLOS(boolean remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs) { 2641 int retval = MotControllerJNI.ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(m_handle, remoteSensorClosedLoopDisableNeutralOnLOS, timeoutMs); 2642 return ErrorCode.valueOf(retval); 2643 } 2644 /** 2645 * Enables clearing the position of the feedback sensor when the forward 2646 * limit switch is triggered. 2647 * 2648 * @param clearPositionOnLimitF Whether clearing is enabled, defaults false 2649 * @param timeoutMs 2650 * Timeout value in ms. If nonzero, function will wait for 2651 * config success and report an error if it times out. 2652 * If zero, no blocking or checking is performed. 2653 * @return Error Code generated by function. 0 indicates no error. 2654 */ 2655 public ErrorCode configClearPositionOnLimitF(boolean clearPositionOnLimitF, int timeoutMs) { 2656 int retval = MotControllerJNI.ConfigClearPositionOnLimitF(m_handle, clearPositionOnLimitF, timeoutMs); 2657 return ErrorCode.valueOf(retval); 2658 } 2659 2660 /** 2661 * Enables clearing the position of the feedback sensor when the reverse 2662 * limit switch is triggered 2663 * 2664 * @param clearPositionOnLimitR Whether clearing is enabled, defaults false 2665 * @param timeoutMs 2666 * Timeout value in ms. If nonzero, function will wait for 2667 * config success and report an error if it times out. 2668 * If zero, no blocking or checking is performed. 2669 * @return Error Code generated by function. 0 indicates no error. 2670 */ 2671 public ErrorCode configClearPositionOnLimitR(boolean clearPositionOnLimitR, int timeoutMs) { 2672 int retval = MotControllerJNI.ConfigClearPositionOnLimitR(m_handle, clearPositionOnLimitR, timeoutMs); 2673 return ErrorCode.valueOf(retval); 2674 } 2675 2676 /** 2677 * Enables clearing the position of the feedback sensor when the quadrature index signal 2678 * is detected 2679 * 2680 * @param clearPositionOnQuadIdx Whether clearing is enabled, defaults false 2681 * @param timeoutMs 2682 * Timeout value in ms. If nonzero, function will wait for 2683 * config success and report an error if it times out. 2684 * If zero, no blocking or checking is performed. 2685 * @return Error Code generated by function. 0 indicates no error. 2686 */ 2687 public ErrorCode configClearPositionOnQuadIdx(boolean clearPositionOnQuadIdx, int timeoutMs) { 2688 int retval = MotControllerJNI.ConfigClearPositionOnQuadIdx(m_handle, clearPositionOnQuadIdx, timeoutMs); 2689 return ErrorCode.valueOf(retval); 2690 } 2691 2692 /** 2693 * Disables limit switches triggering (if enabled) when the sensor is no longer detected. 2694 * 2695 * @param limitSwitchDisableNeutralOnLOS disable triggering 2696 * 2697 * @param timeoutMs 2698 * Timeout value in ms. If nonzero, function will wait for 2699 * config success and report an error if it times out. 2700 * If zero, no blocking or checking is performed. 2701 * @return Error Code generated by function. 0 indicates no error. 2702 */ 2703 public ErrorCode configLimitSwitchDisableNeutralOnLOS(boolean limitSwitchDisableNeutralOnLOS, int timeoutMs) { 2704 int retval = MotControllerJNI.ConfigLimitSwitchDisableNeutralOnLOS(m_handle, limitSwitchDisableNeutralOnLOS, timeoutMs); 2705 return ErrorCode.valueOf(retval); 2706 } 2707 2708 /** 2709 * Disables soft limits triggering (if enabled) when the sensor is no longer detected. 2710 * 2711 * @param softLimitDisableNeutralOnLOS disable triggering 2712 * 2713 * @param timeoutMs 2714 * Timeout value in ms. If nonzero, function will wait for 2715 * config success and report an error if it times out. 2716 * If zero, no blocking or checking is performed. 2717 * @return Error Code generated by function. 0 indicates no error. 2718 */ 2719 public ErrorCode configSoftLimitDisableNeutralOnLOS(boolean softLimitDisableNeutralOnLOS, int timeoutMs) { 2720 int retval = MotControllerJNI.ConfigSoftLimitDisableNeutralOnLOS(m_handle, softLimitDisableNeutralOnLOS, timeoutMs); 2721 return ErrorCode.valueOf(retval); 2722 } 2723 2724 /** 2725 * Sets the edges per rotation of a pulse width sensor. (This should be set for 2726 * tachometer use). 2727 * 2728 * @param pulseWidthPeriod_EdgesPerRot edges per rotation 2729 * 2730 * @param timeoutMs 2731 * Timeout value in ms. If nonzero, function will wait for 2732 * config success and report an error if it times out. 2733 * If zero, no blocking or checking is performed. 2734 * @return Error Code generated by function. 0 indicates no error. 2735 */ 2736 public ErrorCode configPulseWidthPeriod_EdgesPerRot(int pulseWidthPeriod_EdgesPerRot, int timeoutMs) { 2737 int retval = MotControllerJNI.ConfigPulseWidthPeriod_EdgesPerRot(m_handle, pulseWidthPeriod_EdgesPerRot, timeoutMs); 2738 return ErrorCode.valueOf(retval); 2739 } 2740 2741 /** 2742 * Sets the number of samples to use in smoothing a pulse width sensor with a rolling 2743 * average. Default is 1 (no smoothing). 2744 * 2745 * @param pulseWidthPeriod_FilterWindowSz samples for rolling avg 2746 * 2747 * @param timeoutMs 2748 * Timeout value in ms. If nonzero, function will wait for 2749 * config success and report an error if it times out. 2750 * If zero, no blocking or checking is performed. 2751 * @return Error Code generated by function. 0 indicates no error. 2752 */ 2753 public ErrorCode configPulseWidthPeriod_FilterWindowSz(int pulseWidthPeriod_FilterWindowSz, int timeoutMs) { 2754 int retval = MotControllerJNI.ConfigPulseWidthPeriod_FilterWindowSz(m_handle, pulseWidthPeriod_FilterWindowSz, timeoutMs); 2755 return ErrorCode.valueOf(retval); 2756 } 2757 // ------ error ----------// 2758 /** 2759 * Gets the last error generated by this object. Not all functions return an 2760 * error code but can potentially report errors. This function can be used 2761 * to retrieve those error codes. 2762 * 2763 * @return Last Error Code generated by a function. 2764 */ 2765 public ErrorCode getLastError() { 2766 int retval = MotControllerJNI.GetLastError(m_handle); 2767 return ErrorCode.valueOf(retval); 2768 } 2769 2770 // ------ Faults ----------// 2771 /** 2772 * Polls the various fault flags. 2773 * 2774 * @param toFill 2775 * Caller's object to fill with latest fault flags. 2776 * @return Last Error Code generated by a function. 2777 */ 2778 public ErrorCode getFaults(Faults toFill) { 2779 int bits = MotControllerJNI.GetFaults(m_handle); 2780 toFill.update(bits); 2781 return getLastError(); 2782 } 2783 2784 /** 2785 * Polls the various sticky fault flags. 2786 * 2787 * @param toFill 2788 * Caller's object to fill with latest sticky fault flags. 2789 * @return Last Error Code generated by a function. 2790 */ 2791 public ErrorCode getStickyFaults(StickyFaults toFill) { 2792 int bits = MotControllerJNI.GetStickyFaults(m_handle); 2793 toFill.update(bits); 2794 return getLastError(); 2795 } 2796 2797 /** 2798 * Clears all sticky faults. 2799 * 2800 * @param timeoutMs 2801 * Timeout value in ms. If nonzero, function will wait for config 2802 * success and report an error if it times out. If zero, no 2803 * blocking or checking is performed. 2804 * @return Last Error Code generated by a function. 2805 */ 2806 public ErrorCode clearStickyFaults(int timeoutMs) { 2807 int retval = MotControllerJNI.ClearStickyFaults(m_handle, timeoutMs); 2808 return ErrorCode.valueOf(retval); 2809 } 2810 /** 2811 * Clears all sticky faults. 2812 * 2813 * @return Last Error Code generated by a function. 2814 */ 2815 public ErrorCode clearStickyFaults() { 2816 int timeoutMs = 0; 2817 return clearStickyFaults(timeoutMs); 2818 } 2819 2820 // ------ Firmware ----------// 2821 /** 2822 * Gets the firmware version of the device. 2823 * 2824 * @return Firmware version of device. For example: version 1-dot-2 is 2825 * 0x0102. 2826 */ 2827 public int getFirmwareVersion() { 2828 return MotControllerJNI.GetFirmwareVersion(m_handle); 2829 } 2830 2831 /** 2832 * Returns true if the device has reset since last call. 2833 * 2834 * @return Has a Device Reset Occurred? 2835 */ 2836 public boolean hasResetOccurred() { 2837 return MotControllerJNI.HasResetOccurred(m_handle); 2838 } 2839 2840 //------ Custom Persistent Params ----------// 2841 /** 2842 * Sets the value of a custom parameter. This is for arbitrary use. 2843 * 2844 * Sometimes it is necessary to save calibration/limit/target information in 2845 * the device. Particularly if the device is part of a subsystem that can be 2846 * replaced. 2847 * 2848 * @param newValue 2849 * Value for custom parameter. 2850 * @param paramIndex 2851 * Index of custom parameter [0,1] 2852 * @param timeoutMs 2853 * Timeout value in ms. If nonzero, function will wait for config 2854 * success and report an error if it times out. If zero, no 2855 * blocking or checking is performed. 2856 * @return Error Code generated by function. 0 indicates no error. 2857 */ 2858 public ErrorCode configSetCustomParam(int newValue, int paramIndex, int timeoutMs) { 2859 int retval = MotControllerJNI.ConfigSetCustomParam(m_handle, newValue, paramIndex, timeoutMs); 2860 return ErrorCode.valueOf(retval); 2861 } 2862 /** 2863 * Sets the value of a custom parameter. This is for arbitrary use. 2864 * 2865 * Sometimes it is necessary to save calibration/limit/target information in 2866 * the device. Particularly if the device is part of a subsystem that can be 2867 * replaced. 2868 * 2869 * @param newValue 2870 * Value for custom parameter. 2871 * @param paramIndex 2872 * Index of custom parameter [0,1] 2873 * @return Error Code generated by function. 0 indicates no error. 2874 */ 2875 public ErrorCode configSetCustomParam(int newValue, int paramIndex) { 2876 int timeoutMs = 0; 2877 return configSetCustomParam( newValue, paramIndex, timeoutMs); 2878 } 2879 2880 /** 2881 * Gets the value of a custom parameter. 2882 * 2883 * @param paramIndex 2884 * Index of custom parameter [0,1]. 2885 * @param timeoutMs 2886 * Timeout value in ms. If nonzero, function will wait for config 2887 * success and report an error if it times out. If zero, no 2888 * blocking or checking is performed. 2889 * @return Value of the custom param. 2890 */ 2891 public int configGetCustomParam(int paramIndex, int timeoutMs) { 2892 int retval = MotControllerJNI.ConfigGetCustomParam(m_handle, paramIndex, timeoutMs); 2893 return retval; 2894 } 2895 /** 2896 * Gets the value of a custom parameter. 2897 * 2898 * @param paramIndex 2899 * Index of custom parameter [0,1]. 2900 * @return Value of the custom param. 2901 */ 2902 public int configGetCustomParam(int paramIndex) { 2903 int timeoutMs = 0; 2904 return configGetCustomParam( paramIndex, timeoutMs); 2905 } 2906 2907 // ------ Generic Param API ----------// 2908 /** 2909 * Sets a parameter. Generally this is not used. This can be utilized in - 2910 * Using new features without updating API installation. - Errata 2911 * workarounds to circumvent API implementation. - Allows for rapid testing 2912 * / unit testing of firmware. 2913 * 2914 * @param param 2915 * Parameter enumeration. 2916 * @param value 2917 * Value of parameter. 2918 * @param subValue 2919 * Subvalue for parameter. Maximum value of 255. 2920 * @param ordinal 2921 * Ordinal of parameter. 2922 * @param timeoutMs 2923 * Timeout value in ms. If nonzero, function will wait for config 2924 * success and report an error if it times out. If zero, no 2925 * blocking or checking is performed. 2926 * @return Error Code generated by function. 0 indicates no error. 2927 */ 2928 public ErrorCode configSetParameter(ParamEnum param, double value, int subValue, int ordinal, int timeoutMs) { 2929 return configSetParameter(param.value, value, subValue, ordinal, timeoutMs); 2930 } 2931 /** 2932 * Sets a parameter. Generally this is not used. This can be utilized in - 2933 * Using new features without updating API installation. - Errata 2934 * workarounds to circumvent API implementation. - Allows for rapid testing 2935 * / unit testing of firmware. 2936 * 2937 * @param param 2938 * Parameter enumeration. 2939 * @param value 2940 * Value of parameter. 2941 * @param subValue 2942 * Subvalue for parameter. Maximum value of 255. 2943 * @param ordinal 2944 * Ordinal of parameter. 2945 * @return Error Code generated by function. 0 indicates no error. 2946 */ 2947 public ErrorCode configSetParameter(ParamEnum param, double value, int subValue, int ordinal) { 2948 int timeoutMs = 0; 2949 return configSetParameter(param, value, subValue, ordinal, timeoutMs); 2950 } 2951 /** 2952 * Sets a parameter. 2953 * 2954 * @param param 2955 * Parameter enumeration. 2956 * @param value 2957 * Value of parameter. 2958 * @param subValue 2959 * Subvalue for parameter. Maximum value of 255. 2960 * @param ordinal 2961 * Ordinal of parameter. 2962 * @param timeoutMs 2963 * Timeout value in ms. If nonzero, function will wait for 2964 * config success and report an error if it times out. 2965 * If zero, no blocking or checking is performed. 2966 * @return Error Code generated by function. 0 indicates no error. 2967 */ 2968 public ErrorCode configSetParameter(int param, double value, int subValue, int ordinal, int timeoutMs) { 2969 int retval = MotControllerJNI.ConfigSetParameter(m_handle, param, value, subValue, ordinal, 2970 timeoutMs); 2971 return ErrorCode.valueOf(retval); 2972 } 2973 /** 2974 * Sets a parameter. 2975 * 2976 * @param param 2977 * Parameter enumeration. 2978 * @param value 2979 * Value of parameter. 2980 * @param subValue 2981 * Subvalue for parameter. Maximum value of 255. 2982 * @param ordinal 2983 * Ordinal of parameter. 2984 * @return Error Code generated by function. 0 indicates no error. 2985 */ 2986 public ErrorCode configSetParameter(int param, double value, int subValue, int ordinal) { 2987 int timeoutMs = 0; 2988 return configSetParameter( param, value, subValue, ordinal, timeoutMs); 2989 } 2990 /** 2991 * Gets a parameter. 2992 * 2993 * @param param 2994 * Parameter enumeration. 2995 * @param ordinal 2996 * Ordinal of parameter. 2997 * @param timeoutMs 2998 * Timeout value in ms. If nonzero, function will wait for 2999 * config success and report an error if it times out. 3000 * If zero, no blocking or checking is performed. 3001 * @return Value of parameter. 3002 */ 3003 public double configGetParameter(ParamEnum param, int ordinal, int timeoutMs) { 3004 return configGetParameter(param.value, ordinal, timeoutMs); 3005 } 3006 /** 3007 * Gets a parameter. 3008 * 3009 * @param param 3010 * Parameter enumeration. 3011 * @param ordinal 3012 * Ordinal of parameter. 3013 * @return Value of parameter. 3014 */ 3015 public double configGetParameter(ParamEnum param, int ordinal) { 3016 int timeoutMs = 0; 3017 return configGetParameter(param, ordinal, timeoutMs); 3018 } 3019 /** 3020 * Gets a parameter. 3021 * 3022 * @param param 3023 * Parameter enumeration. 3024 * @param ordinal 3025 * Ordinal of parameter. 3026 * @param timeoutMs 3027 * Timeout value in ms. If nonzero, function will wait for 3028 * config success and report an error if it times out. 3029 * If zero, no blocking or checking is performed. 3030 * @return Value of parameter. 3031 */ 3032 public double configGetParameter(int param, int ordinal, int timeoutMs) { 3033 return MotControllerJNI.ConfigGetParameter(m_handle, param, ordinal, timeoutMs); 3034 } 3035 /** 3036 * Gets a parameter. 3037 * 3038 * @param param 3039 * Parameter enumeration. 3040 * @param ordinal 3041 * Ordinal of parameter. 3042 * @return Value of parameter. 3043 */ 3044 public double configGetParameter(int param, int ordinal) { 3045 int timeoutMs = 0; 3046 return configGetParameter( param, ordinal, timeoutMs); 3047 } 3048 3049 // ------ Misc. ----------// 3050 public int getBaseID() { 3051 return MotControllerJNI.GetBaseID(m_handle); 3052 } 3053 3054 /** 3055 * @return control mode motor controller is in 3056 */ 3057 public ControlMode getControlMode() { 3058 return m_controlMode; 3059 } 3060 3061 // ----- Follower ------// 3062 /** 3063 * Set the control mode and output value so that this motor controller will 3064 * follow another motor controller. Currently supports following Victor SPX, 3065 * Talon SRX, and Talon FX. 3066 * 3067 * @param masterToFollow 3068 * Motor Controller object to follow. 3069 * @param followerType 3070 * Type of following control. Use AuxOutput1 to follow the master 3071 * device's auxiliary output 1. 3072 * Use PercentOutput for standard follower mode. 3073 */ 3074 public void follow(IMotorController masterToFollow, FollowerType followerType) { 3075 int id32 = masterToFollow.getBaseID(); 3076 int id24 = id32; 3077 id24 >>= 16; 3078 id24 = (short) id24; 3079 id24 <<= 8; 3080 id24 |= (id32 & 0xFF); 3081 3082 switch (followerType){ 3083 case PercentOutput: 3084 set(ControlMode.Follower, (double)id24); 3085 break; 3086 case AuxOutput1: 3087 /* follow the motor controller, but set the aux flag 3088 * to ensure we follow the processed output */ 3089 set(ControlMode.Follower, (double)id24, DemandType.AuxPID, 0); 3090 break; 3091 default: 3092 neutralOutput(); 3093 break; 3094 } 3095 } 3096 /** 3097 * Set the control mode and output value so that this motor controller will 3098 * follow another motor controller. Currently supports following Victor SPX, 3099 * Talon SRX, and Talon FX. 3100 * 3101 * @param masterToFollow Motor Controller to follow 3102 */ 3103 public void follow(IMotorController masterToFollow) { 3104 follow(masterToFollow, FollowerType.PercentOutput); 3105 } 3106 /** 3107 * When master makes a device, this routine is called to signal the update. 3108 */ 3109 public void valueUpdated() { 3110 // MT 3111 } 3112 3113 //------Config All------// 3114 3115 /** 3116 * Configures all base persistant settings. 3117 * 3118 * @param allConfigs Object with all of the base persistant settings 3119 * @param timeoutMs 3120 * Timeout value in ms. If nonzero, function will wait for 3121 * config success and report an error if it times out. 3122 * If zero, no blocking or checking is performed. 3123 * 3124 * @return Error Code generated by function. 0 indicates no error. 3125 */ 3126 protected ErrorCode baseConfigAllSettings(BaseMotorControllerConfiguration allConfigs, int timeoutMs) { 3127 3128 3129 ErrorCollection errorCollection = new ErrorCollection(); 3130 3131 errorCollection.NewError(configFactoryDefault(timeoutMs)); 3132 3133 if(BaseMotorControllerUtil.openloopRampDifferent(allConfigs)) errorCollection.NewError(configOpenloopRamp(allConfigs.openloopRamp, timeoutMs)); 3134 if(BaseMotorControllerUtil.closedloopRampDifferent(allConfigs)) errorCollection.NewError(configClosedloopRamp(allConfigs.closedloopRamp, timeoutMs)); 3135 if(BaseMotorControllerUtil.peakOutputForwardDifferent(allConfigs)) errorCollection.NewError(configPeakOutputForward(allConfigs.peakOutputForward, timeoutMs)); 3136 if(BaseMotorControllerUtil.peakOutputReverseDifferent(allConfigs)) errorCollection.NewError(configPeakOutputReverse(allConfigs.peakOutputReverse, timeoutMs)); 3137 if(BaseMotorControllerUtil.nominalOutputForwardDifferent(allConfigs)) errorCollection.NewError(configNominalOutputForward(allConfigs.nominalOutputForward, timeoutMs)); 3138 if(BaseMotorControllerUtil.nominalOutputReverseDifferent(allConfigs)) errorCollection.NewError(configNominalOutputReverse(allConfigs.nominalOutputReverse, timeoutMs)); 3139 if(BaseMotorControllerUtil.neutralDeadbandDifferent(allConfigs)) errorCollection.NewError(configNeutralDeadband(allConfigs.neutralDeadband, timeoutMs)); 3140 if(BaseMotorControllerUtil.voltageCompSaturationDifferent(allConfigs)) errorCollection.NewError(configVoltageCompSaturation(allConfigs.voltageCompSaturation, timeoutMs)); 3141 if(BaseMotorControllerUtil.voltageMeasurementFilterDifferent(allConfigs)) errorCollection.NewError(configVoltageMeasurementFilter(allConfigs.voltageMeasurementFilter, timeoutMs)); 3142 if(BaseMotorControllerUtil.velocityMeasurementPeriodDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementPeriod(allConfigs.velocityMeasurementPeriod, timeoutMs)); 3143 if(BaseMotorControllerUtil.velocityMeasurementWindowDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementWindow(allConfigs.velocityMeasurementWindow, timeoutMs)); 3144 if(BaseMotorControllerUtil.forwardSoftLimitThresholdDifferent(allConfigs)) errorCollection.NewError(configForwardSoftLimitThreshold(allConfigs.forwardSoftLimitThreshold, timeoutMs)); 3145 if(BaseMotorControllerUtil.reverseSoftLimitThresholdDifferent(allConfigs)) errorCollection.NewError(configReverseSoftLimitThreshold(allConfigs.reverseSoftLimitThreshold, timeoutMs)); 3146 if(BaseMotorControllerUtil.forwardSoftLimitEnableDifferent(allConfigs)) errorCollection.NewError(configForwardSoftLimitEnable(allConfigs.forwardSoftLimitEnable, timeoutMs)); 3147 if(BaseMotorControllerUtil.reverseSoftLimitEnableDifferent(allConfigs)) errorCollection.NewError(configReverseSoftLimitEnable(allConfigs.reverseSoftLimitEnable, timeoutMs)); 3148 if(BaseMotorControllerUtil.auxPIDPolarityDifferent(allConfigs)) errorCollection.NewError(configAuxPIDPolarity(allConfigs.auxPIDPolarity, timeoutMs)); 3149 if(BaseMotorControllerUtil.motionCruiseVelocityDifferent(allConfigs)) errorCollection.NewError(configMotionCruiseVelocity(allConfigs.motionCruiseVelocity, timeoutMs)); 3150 if(BaseMotorControllerUtil.motionAccelerationDifferent(allConfigs)) errorCollection.NewError(configMotionAcceleration(allConfigs.motionAcceleration, timeoutMs)); 3151 if(BaseMotorControllerUtil.motionSCurveStrength(allConfigs)) errorCollection.NewError(configMotionSCurveStrength(allConfigs.motionCurveStrength, timeoutMs)); 3152 if(BaseMotorControllerUtil.motionProfileTrajectoryPeriodDifferent(allConfigs)) errorCollection.NewError(configMotionProfileTrajectoryPeriod(allConfigs.motionProfileTrajectoryPeriod, timeoutMs)); 3153 if(BaseMotorControllerUtil.feedbackNotContinuousDifferent(allConfigs)) errorCollection.NewError(configFeedbackNotContinuous(allConfigs.feedbackNotContinuous, timeoutMs)); 3154 if(BaseMotorControllerUtil.remoteSensorClosedLoopDisableNeutralOnLOSDifferent(allConfigs)) errorCollection.NewError(configRemoteSensorClosedLoopDisableNeutralOnLOS(allConfigs.remoteSensorClosedLoopDisableNeutralOnLOS, timeoutMs)); 3155 if(BaseMotorControllerUtil.clearPositionOnLimitFDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnLimitF(allConfigs.clearPositionOnLimitF, timeoutMs)); 3156 if(BaseMotorControllerUtil.clearPositionOnLimitRDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnLimitR(allConfigs.clearPositionOnLimitR, timeoutMs)); 3157 if(BaseMotorControllerUtil.clearPositionOnQuadIdxDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnQuadIdx(allConfigs.clearPositionOnQuadIdx, timeoutMs)); 3158 if(BaseMotorControllerUtil.limitSwitchDisableNeutralOnLOSDifferent(allConfigs)) errorCollection.NewError(configLimitSwitchDisableNeutralOnLOS(allConfigs.limitSwitchDisableNeutralOnLOS, timeoutMs)); 3159 if(BaseMotorControllerUtil.softLimitDisableNeutralOnLOSDifferent(allConfigs)) errorCollection.NewError(configSoftLimitDisableNeutralOnLOS(allConfigs.softLimitDisableNeutralOnLOS, timeoutMs)); 3160 if(BaseMotorControllerUtil.pulseWidthPeriod_EdgesPerRotDifferent(allConfigs)) errorCollection.NewError(configPulseWidthPeriod_EdgesPerRot(allConfigs.pulseWidthPeriod_EdgesPerRot, timeoutMs)); 3161 if(BaseMotorControllerUtil.pulseWidthPeriod_FilterWindowSzDifferent(allConfigs)) errorCollection.NewError(configPulseWidthPeriod_FilterWindowSz(allConfigs.pulseWidthPeriod_FilterWindowSz, timeoutMs)); 3162 if(BaseMotorControllerUtil.trajectoryInterpolationEnableDifferent(allConfigs)) errorCollection.NewError(configMotionProfileTrajectoryInterpolationEnable(allConfigs.trajectoryInterpolationEnable, timeoutMs)); 3163 3164 //Custom Parameters 3165 if(BaseMotorControllerUtil.customParam0Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam0, 0, timeoutMs)); 3166 if(BaseMotorControllerUtil.customParam1Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam1, 1, timeoutMs)); 3167 3168 //--------Slots---------------// 3169 errorCollection.NewError(configureSlotPrivate(allConfigs.slot0, 0, timeoutMs, allConfigs.enableOptimizations)); 3170 errorCollection.NewError(configureSlotPrivate(allConfigs.slot1, 1, timeoutMs, allConfigs.enableOptimizations)); 3171 errorCollection.NewError(configureSlotPrivate(allConfigs.slot2, 2, timeoutMs, allConfigs.enableOptimizations)); 3172 errorCollection.NewError(configureSlotPrivate(allConfigs.slot3, 3, timeoutMs, allConfigs.enableOptimizations)); 3173 3174 //----------Remote Feedback Filters----------// 3175 errorCollection.NewError(configureFilter(allConfigs.remoteFilter0, 0, timeoutMs, allConfigs.enableOptimizations)); 3176 errorCollection.NewError(configureFilter(allConfigs.remoteFilter1, 1, timeoutMs, allConfigs.enableOptimizations)); 3177 3178 return errorCollection._worstError; 3179 } 3180 3181 3182 private ErrorCode configureSlotPrivate( SlotConfiguration slot, int slotIdx, int timeoutMs, boolean enableOptimization) { 3183 3184 ErrorCollection errorCollection = new ErrorCollection(); 3185 //------ General Close loop ----------// 3186 3187 3188 3189 if(SlotConfigurationUtil.kPDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kP(slotIdx, slot.kP, timeoutMs)); 3190 if(SlotConfigurationUtil.kIDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kI(slotIdx, slot.kI, timeoutMs)); 3191 if(SlotConfigurationUtil.kDDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kD(slotIdx, slot.kD, timeoutMs)); 3192 if(SlotConfigurationUtil.kFDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kF(slotIdx, slot.kF, timeoutMs)); 3193 if(SlotConfigurationUtil.integralZoneDifferent(slot) || !enableOptimization) errorCollection.NewError(config_IntegralZone(slotIdx, slot.integralZone, timeoutMs)); 3194 if(SlotConfigurationUtil.allowableClosedloopErrorDifferent(slot) || !enableOptimization) errorCollection.NewError(configAllowableClosedloopError(slotIdx, slot.allowableClosedloopError, timeoutMs)); 3195 if(SlotConfigurationUtil.maxIntegralAccumulatorDifferent(slot) || !enableOptimization) errorCollection.NewError(configMaxIntegralAccumulator(slotIdx, slot.maxIntegralAccumulator, timeoutMs)); 3196 if(SlotConfigurationUtil.closedLoopPeakOutputDifferent(slot) || !enableOptimization) errorCollection.NewError(configClosedLoopPeakOutput(slotIdx, slot.closedLoopPeakOutput, timeoutMs)); 3197 if(SlotConfigurationUtil.closedLoopPeriodDifferent(slot) || !enableOptimization) errorCollection.NewError(configClosedLoopPeriod(slotIdx, slot.closedLoopPeriod, timeoutMs)); 3198 3199 return errorCollection._worstError; 3200 3201 } 3202 3203 3204 /** 3205 * Configures all slot persistant settings (overloaded so timeoutMs is 50 ms 3206 * and slotIdx is 0 3207 * 3208 * @param slot Object with all of the slot persistant settings 3209 * 3210 * @return Error Code generated by function. 0 indicates no error. 3211 */ 3212 public ErrorCode configureSlot( SlotConfiguration slot) { 3213 int slotIdx = 0; 3214 int timeoutMs = 50; 3215 return configureSlotPrivate(slot, slotIdx, timeoutMs, false); 3216 } 3217 /** 3218 * Configures all slot persistant settings 3219 * 3220 * @param slot Object with all of the slot persistant settings 3221 * @param slotIdx Index of slot to configure 3222 * @param timeoutMs 3223 * Timeout value in ms. If nonzero, function will wait for 3224 * config success and report an error if it times out. 3225 * If zero, no blocking or checking is performed. 3226 * 3227 * @return Error Code generated by function. 0 indicates no error. 3228 */ 3229 public ErrorCode configureSlot( SlotConfiguration slot, int slotIdx, int timeoutMs) { 3230 return configureSlotPrivate(slot, slotIdx, timeoutMs, false); 3231 } 3232 /** 3233 * Gets all slot persistant settings. 3234 * 3235 * @param slot Object with all of the slot persistant settings 3236 * @param slotIdx Parameter slot for the constant. 3237 * @param timeoutMs 3238 * Timeout value in ms. If nonzero, function will wait for 3239 * config success and report an error if it times out. 3240 * If zero, no blocking or checking is performed. 3241 */ 3242 public void getSlotConfigs(SlotConfiguration slot, int slotIdx, int timeoutMs) { 3243 slot.kP = (double) configGetParameter(ParamEnum.eProfileParamSlot_P, slotIdx, timeoutMs); 3244 slot.kI = (double) configGetParameter(ParamEnum.eProfileParamSlot_I, slotIdx, timeoutMs); 3245 slot.kD = (double) configGetParameter(ParamEnum.eProfileParamSlot_D, slotIdx, timeoutMs); 3246 slot.kF = (double) configGetParameter(ParamEnum.eProfileParamSlot_F, slotIdx, timeoutMs); 3247 slot.integralZone = (int) configGetParameter(ParamEnum.eProfileParamSlot_IZone, slotIdx, timeoutMs); 3248 slot.allowableClosedloopError = (int) configGetParameter(ParamEnum.eProfileParamSlot_AllowableErr, slotIdx, timeoutMs); 3249 slot.maxIntegralAccumulator = (double) configGetParameter(ParamEnum.eProfileParamSlot_MaxIAccum, slotIdx, timeoutMs); 3250 slot.closedLoopPeakOutput = (double) configGetParameter(ParamEnum.eProfileParamSlot_PeakOutput, slotIdx, timeoutMs); 3251 slot.closedLoopPeriod = (int) configGetParameter(ParamEnum.ePIDLoopPeriod, slotIdx, timeoutMs); 3252 } 3253 /** 3254 * Gets all slot persistant settings (overloaded so timeoutMs is 50 ms 3255 * and slotIdx is 0 3256 * 3257 * @param slot Object with all of the slot persistant settings 3258 */ 3259 public void getSlotConfigs( SlotConfiguration slot) { 3260 int slotIdx = 0; 3261 int timeoutMs = 50; 3262 getSlotConfigs(slot, slotIdx, timeoutMs); 3263 } 3264 3265 3266 /** 3267 * Configures all filter persistant settings. 3268 * 3269 * @deprecated Use the 3-parameter configureFilter. 4-param version is deprecated and will be removed. 3270 * @param filter Object with all of the filter persistant settings 3271 * @param ordinal 0 for remote sensor 0 and 1 for remote sensor 1. 3272 * @param timeoutMs 3273 * Timeout value in ms. If nonzero, function will wait for 3274 * config success and report an error if it times out. 3275 * If zero, no blocking or checking is performed. 3276 * @param enableOptimizations Enable the optimization technique 3277 * 3278 * @return Error Code generated by function. 0 indicates no error. 3279 */ 3280 @Deprecated 3281 public ErrorCode configureFilter( FilterConfiguration filter, int ordinal, int timeoutMs, boolean enableOptimizations) { 3282 if(FilterConfigUtil.filterConfigurationDifferent(filter) || !enableOptimizations) 3283 return configRemoteFeedbackFilter(filter.remoteSensorDeviceID, filter.remoteSensorSource, ordinal, timeoutMs); 3284 3285 return ErrorCode.OK; 3286 } 3287 /** 3288 * Configures all filter persistant settings. 3289 * 3290 * @deprecated Use configAll instead. 3291 * @param filter Object with all of the filter persistant settings 3292 * @param ordinal 0 for remote sensor 0 and 1 for remote sensor 1. 3293 * @param timeoutMs 3294 * Timeout value in ms. If nonzero, function will wait for 3295 * config success and report an error if it times out. 3296 * If zero, no blocking or checking is performed. 3297 * 3298 * @return Error Code generated by function. 0 indicates no error. 3299 */ 3300 @Deprecated 3301 public ErrorCode configureFilter( FilterConfiguration filter, int ordinal, int timeoutMs) { 3302 return configureFilter(filter, ordinal, timeoutMs, false); 3303 } 3304 /** 3305 * Configures all filter persistant settings (overloaded so timeoutMs is 50 ms 3306 * and ordinal is 0). 3307 * 3308 * @deprecated Use configAll instead. 3309 * @param filter Object with all of the filter persistant settings 3310 * 3311 * @return Error Code generated by function. 0 indicates no error. 3312 */ 3313 @Deprecated 3314 public ErrorCode configureFilter( FilterConfiguration filter) { 3315 int ordinal = 0; 3316 int timeoutMs = 50; 3317 return configureFilter(filter, ordinal, timeoutMs, false); 3318 } 3319 3320 /** 3321 * Gets all filter persistant settings. 3322 * 3323 * @param filter Object with all of the filter persistant settings 3324 * @param ordinal 0 for remote sensor 0 and 1 for remote sensor 1. 3325 * @param timeoutMs 3326 * Timeout value in ms. If nonzero, function will wait for 3327 * config success and report an error if it times out. 3328 * If zero, no blocking or checking is performed. 3329 */ 3330 public void getFilterConfigs(FilterConfiguration filter, int ordinal, int timeoutMs) { 3331 3332 filter.remoteSensorDeviceID = (int) configGetParameter(ParamEnum.eRemoteSensorDeviceID, ordinal, timeoutMs); 3333 filter.remoteSensorSource = RemoteSensorSource.valueOf(configGetParameter(ParamEnum.eRemoteSensorSource, ordinal, timeoutMs)); 3334 3335 } 3336 /** 3337 * Gets all filter persistant settings (overloaded so timeoutMs is 50 ms 3338 * and ordinal is 0). 3339 * 3340 * @param filter Object with all of the filter persistant settings 3341 */ 3342 public void getFilterConfigs(FilterConfiguration filter) { 3343 int ordinal = 0; 3344 int timeoutMs = 50; 3345 getFilterConfigs(filter, ordinal, timeoutMs); 3346 } 3347 /** 3348 * Configures all base PID set persistant settings. 3349 * 3350 * @param pid Object with all of the base PID set persistant settings 3351 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop. 3352 * @param timeoutMs 3353 * Timeout value in ms. If nonzero, function will wait for 3354 * config success and report an error if it times out. 3355 * If zero, no blocking or checking is performed. 3356 * 3357 * @return Error Code generated by function. 0 indicates no error. 3358 */ 3359 protected ErrorCode baseConfigurePID(BasePIDSetConfiguration pid, int pidIdx, int timeoutMs) { 3360 3361 return configSelectedFeedbackCoefficient(pid.selectedFeedbackCoefficient, pidIdx, timeoutMs); 3362 3363 } 3364 /** 3365 * Gets all base PID set persistant settings. 3366 * 3367 * @param pid Object with all of the base PID set persistant settings 3368 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop. 3369 * @param timeoutMs 3370 * Timeout value in ms. If nonzero, function will wait for 3371 * config success and report an error if it times out. 3372 * If zero, no blocking or checking is performed. 3373 */ 3374 protected void baseGetPIDConfigs(BasePIDSetConfiguration pid, int pidIdx, int timeoutMs) { 3375 3376 pid.selectedFeedbackCoefficient = (double) configGetParameter(ParamEnum.eSelectedSensorCoefficient, pidIdx, timeoutMs); 3377 3378 } 3379 /** 3380 * Gets all base persistant settings. 3381 * 3382 * @param allConfigs Object with all of the base persistant settings 3383 * @param timeoutMs 3384 * Timeout value in ms. If nonzero, function will wait for 3385 * config success and report an error if it times out. 3386 * If zero, no blocking or checking is performed. 3387 */ 3388 protected void baseGetAllConfigs(BaseMotorControllerConfiguration allConfigs, int timeoutMs) { 3389 3390 3391 allConfigs.openloopRamp = (double) configGetParameter(ParamEnum.eOpenloopRamp, 0, timeoutMs); 3392 allConfigs.closedloopRamp = (double) configGetParameter(ParamEnum.eClosedloopRamp, 0, timeoutMs); 3393 allConfigs.peakOutputForward = (double) configGetParameter(ParamEnum.ePeakPosOutput, 0, timeoutMs); 3394 allConfigs.peakOutputReverse = (double) configGetParameter(ParamEnum.ePeakNegOutput, 0, timeoutMs); 3395 allConfigs.nominalOutputForward = (double) configGetParameter(ParamEnum.eNominalPosOutput, 0, timeoutMs); 3396 allConfigs.nominalOutputReverse = (double) configGetParameter(ParamEnum.eNominalNegOutput, 0, timeoutMs); 3397 allConfigs.neutralDeadband = (double) configGetParameter(ParamEnum.eNeutralDeadband, 0, timeoutMs); 3398 allConfigs.voltageCompSaturation = (double) configGetParameter(ParamEnum.eNominalBatteryVoltage, 0, timeoutMs); 3399 allConfigs.voltageMeasurementFilter = (int) configGetParameter(ParamEnum.eBatteryVoltageFilterSize, 0, timeoutMs); 3400 allConfigs.velocityMeasurementPeriod = SensorVelocityMeasPeriod.valueOf(configGetParameter(ParamEnum.eSampleVelocityPeriod, 0, timeoutMs)); 3401 allConfigs.velocityMeasurementWindow = (int) configGetParameter(ParamEnum.eSampleVelocityWindow, 0, timeoutMs); 3402 allConfigs.forwardSoftLimitThreshold = (int) configGetParameter(ParamEnum.eForwardSoftLimitThreshold, 0, timeoutMs); 3403 allConfigs.reverseSoftLimitThreshold = (int) configGetParameter(ParamEnum.eReverseSoftLimitThreshold, 0, timeoutMs); 3404 allConfigs.forwardSoftLimitEnable = configGetParameter(ParamEnum.eForwardSoftLimitEnable, 0, timeoutMs) != 0.0; 3405 allConfigs.reverseSoftLimitEnable = configGetParameter(ParamEnum.eReverseSoftLimitEnable, 0, timeoutMs) != 0.0; //Note, fix in firmware 3406 3407 getSlotConfigs(allConfigs.slot0, 0, timeoutMs); 3408 getSlotConfigs(allConfigs.slot1, 1, timeoutMs); 3409 getSlotConfigs(allConfigs.slot2, 2, timeoutMs); 3410 getSlotConfigs(allConfigs.slot3, 3, timeoutMs); 3411 3412 allConfigs.auxPIDPolarity = configGetParameter(ParamEnum.ePIDLoopPolarity, 1, timeoutMs) != 0.0; 3413 3414 getFilterConfigs(allConfigs.remoteFilter0, 0, timeoutMs); 3415 getFilterConfigs(allConfigs.remoteFilter1, 1, timeoutMs); 3416 3417 allConfigs.motionCruiseVelocity = (int) configGetParameter(ParamEnum.eMotMag_VelCruise, 0, timeoutMs); 3418 allConfigs.motionAcceleration = (int) configGetParameter(ParamEnum.eMotMag_Accel, 0, timeoutMs); 3419 allConfigs.motionCurveStrength = (int) configGetParameter(ParamEnum.eMotMag_SCurveLevel, 0, timeoutMs); 3420 allConfigs.motionProfileTrajectoryPeriod = (int) configGetParameter(ParamEnum.eMotionProfileTrajectoryPointDurationMs, 0, timeoutMs); 3421 allConfigs.customParam0 = (int) configGetParameter(ParamEnum.eCustomParam, 0, timeoutMs); 3422 allConfigs.customParam1 = (int) configGetParameter(ParamEnum.eCustomParam, 1, timeoutMs); 3423 3424 3425 allConfigs.feedbackNotContinuous = configGetParameter(ParamEnum.eFeedbackNotContinuous, 0, timeoutMs) != 0.0; 3426 allConfigs.remoteSensorClosedLoopDisableNeutralOnLOS = configGetParameter(ParamEnum.eRemoteSensorClosedLoopDisableNeutralOnLOS, 0, timeoutMs) != 0.0; 3427 allConfigs.clearPositionOnLimitF = configGetParameter(ParamEnum.eClearPositionOnLimitF, 0, timeoutMs) != 0.0; 3428 allConfigs.clearPositionOnLimitR = configGetParameter(ParamEnum.eClearPositionOnLimitR, 0, timeoutMs) != 0.0; 3429 allConfigs.clearPositionOnQuadIdx = configGetParameter(ParamEnum.eClearPositionOnQuadIdx, 0, timeoutMs) != 0.0; 3430 allConfigs.limitSwitchDisableNeutralOnLOS = configGetParameter(ParamEnum.eLimitSwitchDisableNeutralOnLOS, 0, timeoutMs) != 0.0; 3431 allConfigs.softLimitDisableNeutralOnLOS = configGetParameter(ParamEnum.eSoftLimitDisableNeutralOnLOS, 0, timeoutMs) != 0.0; 3432 allConfigs.pulseWidthPeriod_EdgesPerRot = (int) configGetParameter(ParamEnum.ePulseWidthPeriod_EdgesPerRot, 0, timeoutMs); 3433 allConfigs.pulseWidthPeriod_FilterWindowSz = (int) configGetParameter(ParamEnum.ePulseWidthPeriod_FilterWindowSz, 0, timeoutMs); 3434 3435 3436 } 3437 3438}