Class WPI_VictorSPX

All Implemented Interfaces:
IFollower, IMotorController, IInvertable, IOutputSignal, Sendable, MotorController, AutoCloseable

public class WPI_VictorSPX
extends VictorSPX
implements MotorController, Sendable, AutoCloseable
VEX Victor SPX Motor Controller when used on CAN Bus.
  • Field Details

  • Constructor Details

    • WPI_VictorSPX

      public WPI_VictorSPX​(int deviceNumber)
      Constructor for motor controller
      Parameters:
      deviceNumber - device ID of motor controller
  • Method Details

    • close

      public void close()
      Specified by:
      close in interface AutoCloseable
    • set

      public void set​(double speed)
      Common interface for setting the speed of a simple speed controller.
      Specified by:
      set in interface MotorController
      Parameters:
      speed - The speed to set. Value should be between -1.0 and 1.0. Value is also saved for Get().
    • get

      public double get()
      Common interface for getting the current set speed of a speed controller.
      Specified by:
      get in interface MotorController
      Returns:
      The current set speed. Value is between -1.0 and 1.0.
    • set

      public void set​(ControlMode mode, double value)
      Sets the appropriate output on the talon, depending on the mode.
      Specified by:
      set in interface IMotorController
      Overrides:
      set in class BaseMotorController
      Parameters:
      mode - The output mode to apply. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. In Follower mode, the output value is the integer device ID of the talon to duplicate.
      value - The setpoint value, as described above. Standard Driving Example: _talonLeft.set(ControlMode.PercentOutput, leftJoy); _talonRght.set(ControlMode.PercentOutput, rghtJoy);
    • set

      public void set​(ControlMode mode, double demand0, DemandType demand1Type, double demand1)
      Specified by:
      set in interface IMotorController
      Overrides:
      set in class BaseMotorController
      Parameters:
      mode - Sets the appropriate output on the talon, depending on the mode.
      demand0 - The output value to apply. such as advanced feed forward and/or auxiliary close-looping in firmware. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. See In Follower mode, the output value is the integer device ID of the talon to duplicate.
      demand1Type - The demand type for demand1. Neutral: Ignore demand1 and apply no change to the demand0 output. AuxPID: Use demand1 to set the target for the auxiliary PID 1. ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the demand0 output. In PercentOutput the demand0 output is the motor output, and in closed-loop modes the demand0 output is the output of PID0.
      demand1 - Supplmental output value. Units match the set mode. Arcade Drive Example: _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn); _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn); Drive Straight Example: Note: Selected Sensor Configuration is necessary for both PID0 and PID1. _talonLeft.follow(_talonRght, FollwerType.AuxOutput1); _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading); Drive Straight to a Distance Example: Note: Other configurations (sensor selection, PID gains, etc.) need to be set. _talonLeft.follow(_talonRght, FollwerType.AuxOutput1); _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
    • setVoltage

      public void setVoltage​(double outputVolts)
      Sets the voltage output of the MotorController. Compensates for the current bus voltage to ensure that the desired voltage is output even if the battery voltage is below 12V - highly useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward calculation).

      NOTE: This function *must* be called regularly in order for voltage compensation to work properly - unlike the ordinary set function, it is not "set it and forget it."

      Specified by:
      setVoltage in interface MotorController
      Parameters:
      outputVolts - The voltage to output.
    • setInverted

      public void setInverted​(boolean isInverted)
      Common interface for inverting direction of a speed controller.
      Specified by:
      setInverted in interface IInvertable
      Specified by:
      setInverted in interface IMotorController
      Specified by:
      setInverted in interface MotorController
      Overrides:
      setInverted in class BaseMotorController
      Parameters:
      isInverted - The state of inversion, true is inverted.
    • getInverted

      public boolean getInverted()
      Common interface for returning the inversion state of a speed controller.
      Specified by:
      getInverted in interface IInvertable
      Specified by:
      getInverted in interface IMotorController
      Specified by:
      getInverted in interface MotorController
      Overrides:
      getInverted in class BaseMotorController
      Returns:
      The state of inversion, true is inverted.
    • disable

      public void disable()
      Common interface for disabling a motor.
      Specified by:
      disable in interface MotorController
    • stopMotor

      public void stopMotor()
      Common interface to stop the motor until Set is called again.
      Specified by:
      stopMotor in interface MotorController
    • initSendable

      public void initSendable​(SendableBuilder builder)
      Initialize sendable
      Specified by:
      initSendable in interface Sendable
      Parameters:
      builder - Base sendable to build on
    • getDescription

      Returns:
      description of controller
    • feed

      public void feed()
      Feed the motor safety object.

      Resets the timer on this object that is used to do the timeouts.

    • setExpiration

      public void setExpiration​(double expirationTime)
      Set the expiration time for the corresponding motor safety object.
      Parameters:
      expirationTime - The timeout value in seconds.
    • getExpiration

      public double getExpiration()
      Retrieve the timeout value for the corresponding motor safety object.
      Returns:
      the timeout value in seconds.
    • isAlive

      public boolean isAlive()
      Determine of the motor is still operating or has timed out.
      Returns:
      a true value if the motor is still operating normally and hasn't timed out.
    • setSafetyEnabled

      public void setSafetyEnabled​(boolean enabled)
      Enable/disable motor safety for this device.

      Turn on and off the motor safety option for this PWM object.

      Parameters:
      enabled - True if motor safety is enforced for this object
    • isSafetyEnabled

      public boolean isSafetyEnabled()
      Return the state of the motor safety enabled flag.

      Return if the motor safety is currently enabled for this device.

      Returns:
      True if motor safety is enforced for this device