Class VictorSPX
java.lang.Object
com.ctre.phoenix.motorcontrol.can.BaseMotorController
com.ctre.phoenix.motorcontrol.can.VictorSPX
- All Implemented Interfaces:
IFollower
,IMotorController
,IInvertable
,IOutputSignal
- Direct Known Subclasses:
WPI_VictorSPX
public class VictorSPX extends BaseMotorController implements IMotorController
VEX Victor SPX Motor Controller when used on CAN Bus.
// Example usage of a VictorSPX motor controller
VictorSPX motor = new VictorSPX(0); // creates a new VictorSPX with ID 0
motor.set(VictorSPXControlMode.PercentOutput, 0.5); // runs the motor at 50% power
System.out.println(motor.getMotorOutputPercent()); // prints the percent output of the motor (0.5)
System.out.println(motor.getBusVoltage()); // prints the bus voltage seen by the motor controller
ErrorCode error = motor.getLastError(); // gets the last error generated by the motor controller
Faults faults = new Faults();
ErrorCode faultsError = motor.getFaults(faults); // fills faults with the current motor controller faults; returns the last error generated
-
Field Summary
-
Constructor Summary
Constructors Constructor Description VictorSPX(int deviceNumber)
Constructor -
Method Summary
Modifier and Type Method Description ErrorCode
configAllSettings(VictorSPXConfiguration allConfigs)
Configures all persistent settings (overloaded so timeoutMs is 50 ms).ErrorCode
configAllSettings(VictorSPXConfiguration allConfigs, int timeoutMs)
Configures all persistent settings.void
getAllConfigs(VictorSPXConfiguration allConfigs)
Gets all persistant settings (overloaded so timeoutMs is 50 ms).void
getAllConfigs(VictorSPXConfiguration allConfigs, int timeoutMs)
Gets all persistant settings.void
getPIDConfigs(VictorSPXPIDSetConfiguration pid)
Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).void
getPIDConfigs(VictorSPXPIDSetConfiguration pid, int pidIdx, int timeoutMs)
Gets all PID set persistant settings.VictorSPXSimCollection
getSimCollection()
void
set(VictorSPXControlMode mode, double value)
Sets the appropriate output on the motor controller, depending on the mode.void
set(VictorSPXControlMode mode, double demand0, DemandType demand1Type, double demand1)
Methods inherited from class com.ctre.phoenix.motorcontrol.can.BaseMotorController
baseConfigAllSettings, baseConfigurePID, baseGetAllConfigs, baseGetPIDConfigs, changeMotionControlFramePeriod, clearMotionProfileHasUnderrun, clearMotionProfileHasUnderrun, clearMotionProfileTrajectories, clearStickyFaults, clearStickyFaults, config_IntegralZone, config_IntegralZone, config_kD, config_kD, config_kF, config_kF, config_kI, config_kI, config_kP, config_kP, configAllowableClosedloopError, configAllowableClosedloopError, configAuxPIDPolarity, configAuxPIDPolarity, configClearPositionOnLimitF, configClearPositionOnLimitR, configClearPositionOnQuadIdx, configClosedLoopPeakOutput, configClosedLoopPeakOutput, configClosedLoopPeriod, configClosedLoopPeriod, configClosedloopRamp, configClosedloopRamp, configFactoryDefault, configFactoryDefault, configFeedbackNotContinuous, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardSoftLimitEnable, configForwardSoftLimitEnable, configForwardSoftLimitThreshold, configForwardSoftLimitThreshold, configGetCustomParam, configGetCustomParam, configGetParameter, configGetParameter, configGetParameter, configGetParameter, configLimitSwitchDisableNeutralOnLOS, configMaxIntegralAccumulator, configMaxIntegralAccumulator, configMotionAcceleration, configMotionAcceleration, configMotionCruiseVelocity, configMotionCruiseVelocity, configMotionProfileTrajectoryInterpolationEnable, configMotionProfileTrajectoryInterpolationEnable, configMotionProfileTrajectoryPeriod, configMotionProfileTrajectoryPeriod, configMotionSCurveStrength, configMotionSCurveStrength, configNeutralDeadband, configNeutralDeadband, configNominalOutputForward, configNominalOutputForward, configNominalOutputReverse, configNominalOutputReverse, configOpenloopRamp, configOpenloopRamp, configPeakOutputForward, configPeakOutputForward, configPeakOutputReverse, configPeakOutputReverse, configPulseWidthPeriod_EdgesPerRot, configPulseWidthPeriod_FilterWindowSz, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteSensorClosedLoopDisableNeutralOnLOS, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configReverseSoftLimitEnable, configReverseSoftLimitEnable, configReverseSoftLimitThreshold, configReverseSoftLimitThreshold, configSelectedFeedbackCoefficient, configSelectedFeedbackCoefficient, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSensorTerm, configSensorTerm, configSensorTerm, configSensorTerm, configSetCustomParam, configSetCustomParam, configSetParameter, configSetParameter, configSetParameter, configSetParameter, configSoftLimitDisableNeutralOnLOS, configureFilter, configureFilter, configureFilter, configureSlot, configureSlot, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementWindow, configVelocityMeasurementWindow, configVoltageCompSaturation, configVoltageCompSaturation, configVoltageMeasurementFilter, configVoltageMeasurementFilter, DestroyObject, enableVoltageCompensation, follow, follow, getActiveTrajectoryArbFeedFwd, getActiveTrajectoryArbFeedFwd, getActiveTrajectoryPosition, getActiveTrajectoryPosition, getActiveTrajectoryVelocity, getActiveTrajectoryVelocity, getBaseID, getBusVoltage, getClosedLoopError, getClosedLoopError, getClosedLoopTarget, getClosedLoopTarget, getControlMode, getDeviceID, getErrorDerivative, getErrorDerivative, getFaults, getFilterConfigs, getFilterConfigs, getFirmwareVersion, getHandle, getIntegralAccumulator, getIntegralAccumulator, getInverted, getLastError, getMotionProfileStatus, getMotionProfileTopLevelBufferCount, getMotorOutputPercent, getMotorOutputVoltage, getOutputCurrent, getSelectedSensorPosition, getSelectedSensorPosition, getSelectedSensorVelocity, getSelectedSensorVelocity, getSlotConfigs, getSlotConfigs, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStickyFaults, getTemperature, getVictorSPXSimCollection, hasResetOccurred, isMotionProfileFinished, isMotionProfileTopLevelBufferFull, isVoltageCompensationEnabled, neutralOutput, overrideLimitSwitchesEnable, overrideSoftLimitsEnable, processMotionProfileBuffer, pushMotionProfileTrajectory, selectProfileSlot, set, set, setControlFramePeriod, setControlFramePeriod, setIntegralAccumulator, setIntegralAccumulator, setInverted, setInverted, setNeutralMode, setSelectedSensorPosition, setSelectedSensorPosition, setSensorPhase, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, startMotionProfile, valueUpdated
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface com.ctre.phoenix.motorcontrol.IMotorController
changeMotionControlFramePeriod, clearMotionProfileHasUnderrun, clearMotionProfileTrajectories, clearStickyFaults, config_IntegralZone, config_kD, config_kF, config_kI, config_kP, configAllowableClosedloopError, configAuxPIDPolarity, configClosedLoopPeakOutput, configClosedLoopPeriod, configClosedloopRamp, configForwardLimitSwitchSource, configForwardSoftLimitEnable, configForwardSoftLimitThreshold, configGetCustomParam, configGetParameter, configGetParameter, configMaxIntegralAccumulator, configMotionAcceleration, configMotionCruiseVelocity, configMotionProfileTrajectoryPeriod, configMotionSCurveStrength, configNeutralDeadband, configNominalOutputForward, configNominalOutputReverse, configOpenloopRamp, configPeakOutputForward, configPeakOutputReverse, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configReverseLimitSwitchSource, configReverseSoftLimitEnable, configReverseSoftLimitThreshold, configSelectedFeedbackCoefficient, configSelectedFeedbackSensor, configSensorTerm, configSetCustomParam, configSetParameter, configSetParameter, configVoltageCompSaturation, configVoltageMeasurementFilter, enableVoltageCompensation, getActiveTrajectoryPosition, getActiveTrajectoryVelocity, getBaseID, getBusVoltage, getClosedLoopError, getClosedLoopTarget, getControlMode, getDeviceID, getErrorDerivative, getFaults, getFirmwareVersion, getIntegralAccumulator, getInverted, getLastError, getMotionProfileStatus, getMotionProfileTopLevelBufferCount, getMotorOutputPercent, getMotorOutputVoltage, getSelectedSensorPosition, getSelectedSensorVelocity, getStatusFramePeriod, getStickyFaults, getTemperature, hasResetOccurred, isMotionProfileTopLevelBufferFull, neutralOutput, overrideLimitSwitchesEnable, overrideSoftLimitsEnable, processMotionProfileBuffer, pushMotionProfileTrajectory, selectProfileSlot, set, set, setControlFramePeriod, setIntegralAccumulator, setInverted, setInverted, setNeutralMode, setSelectedSensorPosition, setSensorPhase, setStatusFramePeriod
-
Constructor Details
-
VictorSPX
Constructor- Parameters:
deviceNumber
- [0,62]
-
-
Method Details
-
set
Sets the appropriate output on the motor controller, depending on the mode.- Parameters:
mode
- The output mode to apply. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. 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 motor controller to duplicate.value
- The setpoint value, as described above. Standard Driving Example: _victorLeft.set(ControlMode.PercentOutput, leftJoy); _victorRght.set(ControlMode.PercentOutput, rghtJoy);
-
set
- Parameters:
mode
- Sets the appropriate output on the motor controller, 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 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 motor controller 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. Auxiliary PID is always executed as standard Position PID control. 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. AuxPID: Target position in Sensor Units ArbitraryFeedForward: Percent Output between -1.0 and 1.0 Arcade Drive Example: _victorLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn); _victorRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn); Drive Straight Example: Note: Selected Sensor Configuration is necessary for both PID0 and PID1. _victorLeft.follow(_victorRght, FollwerType.AuxOutput1); _victorRght.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. _victorLeft.follow(_victorRght, FollwerType.AuxOutput1); _victorRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
-
getSimCollection
- Returns:
- object that can get/set simulation inputs.
-
getPIDConfigs
Gets all PID set persistant settings.- Parameters:
pid
- Object with all of the PID set persistant settingspidIdx
- 0 for Primary closed-loop. 1 for auxiliary closed-loop.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
-
getPIDConfigs
Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).- Parameters:
pid
- Object with all of the PID set persistant settings
-
configAllSettings
Configures all persistent settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configAllSettings
Configures all persistent settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings- Returns:
- Error Code generated by function. 0 indicates no error.
-
getAllConfigs
Gets all persistant settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
-
getAllConfigs
Gets all persistant settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings
-