CTRE Phoenix C++ 5.33.0
ctre::phoenix::motorcontrol::can::VictorSPX Class Reference

VEX Victor SPX Motor Controller when used on CAN Bus. More...

#include <ctre/phoenix/motorcontrol/can/VictorSPX.h>

Inheritance diagram for ctre::phoenix::motorcontrol::can::VictorSPX:
ctre::phoenix::motorcontrol::can::BaseMotorController ctre::phoenix::motorcontrol::IMotorController ctre::phoenix::motorcontrol::IMotorController ctre::phoenix::motorcontrol::IFollower ctre::phoenix::motorcontrol::IFollower ctre::phoenix::motorcontrol::can::WPI_VictorSPX

Public Member Functions

 VictorSPX (int deviceNumber)
 Constructor. More...
 
 VictorSPX (int deviceNumber, std::string const &canbus)
 Constructor so non-FRC platforms can specify a CAN 2.0 socketcan bus. More...
 
virtual ~VictorSPX ()
 
 VictorSPX (VictorSPX const &)=delete
 
VictorSPXoperator= (VictorSPX const &)=delete
 
void Set (ctre::phoenix::motorcontrol::VictorSPXControlMode mode, double value)
 Sets the appropriate output on the motor controller, depending on the mode. More...
 
void Set (ctre::phoenix::motorcontrol::VictorSPXControlMode mode, double demand0, ctre::phoenix::motorcontrol::DemandType demand1Type, double demand1)
 
ctre::phoenix::motorcontrol::VictorSPXSimCollectionGetSimCollection ()
 
void GetPIDConfigs (VictorSPXPIDSetConfiguration &pid, int pidIdx=0, int timeoutMs=50)
 Gets all PID set persistant settings. More...
 
virtual ctre::phoenix::ErrorCode ConfigAllSettings (const VictorSPXConfiguration &allConfigs, int timeoutMs=50)
 Configures all persistent settings. More...
 
virtual void GetAllConfigs (VictorSPXConfiguration &allConfigs, int timeoutMs=50)
 Gets all persistant settings. More...
 
virtual void Set (ctre::phoenix::motorcontrol::ControlMode mode, double value)
 Sets the appropriate output on the talon, depending on the mode. More...
 
virtual void Set (ctre::phoenix::motorcontrol::ControlMode mode, double demand0, ctre::phoenix::motorcontrol::DemandType demand1Type, double demand1)
 
- Public Member Functions inherited from ctre::phoenix::motorcontrol::can::BaseMotorController
 BaseMotorController (int deviceNumber, const char *model, std::string const &canbus="")
 Constructor for motor controllers. More...
 
virtual ~BaseMotorController ()
 
 BaseMotorController ()=delete
 
 BaseMotorController (BaseMotorController const &)=delete
 
BaseMotorControlleroperator= (BaseMotorController const &)=delete
 
virtual int GetDeviceID ()
 Returns the Device ID. More...
 
virtual void Set (ControlMode mode, double value)
 Sets the appropriate output on the talon, depending on the mode. More...
 
virtual void Set (ControlMode mode, double demand0, DemandType demand1Type, double demand1)
 
virtual void NeutralOutput ()
 Neutral the motor output by setting control mode to disabled. More...
 
virtual void SetNeutralMode (NeutralMode neutralMode)
 Sets the mode of operation during neutral throttle output. More...
 
virtual void SetSensorPhase (bool PhaseSensor)
 Sets the phase of the sensor. More...
 
virtual void SetInverted (bool invert)
 Inverts the hbridge output of the motor controller. More...
 
virtual void SetInverted (InvertType invertType)
 Inverts the hbridge output of the motor controller in relation to the master if present. More...
 
virtual bool GetInverted () const
 
virtual ctre::phoenix::ErrorCode ConfigFactoryDefault (int timeoutMs=50)
 Revert all configurations to factory default values. More...
 
virtual ctre::phoenix::ErrorCode ConfigOpenloopRamp (double secondsFromNeutralToFull, int timeoutMs=0)
 Configures the open-loop ramp rate of throttle output. More...
 
virtual ctre::phoenix::ErrorCode ConfigClosedloopRamp (double secondsFromNeutralToFull, int timeoutMs=0)
 Configures the closed-loop ramp rate of throttle output. More...
 
virtual ctre::phoenix::ErrorCode ConfigPeakOutputForward (double percentOut, int timeoutMs=0)
 Configures the forward peak output percentage. More...
 
virtual ctre::phoenix::ErrorCode ConfigPeakOutputReverse (double percentOut, int timeoutMs=0)
 Configures the reverse peak output percentage. More...
 
virtual ctre::phoenix::ErrorCode ConfigNominalOutputForward (double percentOut, int timeoutMs=0)
 Configures the forward nominal output percentage. More...
 
virtual ctre::phoenix::ErrorCode ConfigNominalOutputReverse (double percentOut, int timeoutMs=0)
 Configures the reverse nominal output percentage. More...
 
virtual ctre::phoenix::ErrorCode ConfigNeutralDeadband (double percentDeadband, int timeoutMs=0)
 Configures the output deadband percentage. More...
 
virtual ctre::phoenix::ErrorCode ConfigVoltageCompSaturation (double voltage, int timeoutMs=0)
 Configures the Voltage Compensation saturation voltage. More...
 
virtual ctre::phoenix::ErrorCode ConfigVoltageMeasurementFilter (int filterWindowSamples, int timeoutMs=0)
 Configures the voltage measurement filter. More...
 
virtual void EnableVoltageCompensation (bool enable)
 Enables voltage compensation. More...
 
virtual bool IsVoltageCompensationEnabled ()
 Returns the enable state of Voltage Compensation that the caller has set. More...
 
virtual double GetBusVoltage ()
 Gets the bus voltage seen by the device. More...
 
virtual double GetMotorOutputPercent ()
 Gets the output percentage of the motor controller. More...
 
virtual double GetMotorOutputVoltage ()
 
virtual double GetTemperature ()
 Gets the temperature of the motor controller. More...
 
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor (RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
 Select the remote feedback device for the motor controller. More...
 
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor (FeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
 Select the feedback device for the motor controller. More...
 
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackCoefficient (double coefficient, int pidIdx=0, int timeoutMs=0)
 The Feedback Coefficient is a scalar applied to the value of the feedback sensor. More...
 
virtual ctre::phoenix::ErrorCode ConfigRemoteFeedbackFilter (int deviceID, RemoteSensorSource remoteSensorSource, int remoteOrdinal, int timeoutMs=0)
 Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. More...
 
virtual ErrorCode ConfigRemoteFeedbackFilter (ctre::phoenix::sensors::CANCoder &canCoderRef, int remoteOrdinal, int timeoutMs=0)
 Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. More...
 
virtual ErrorCode ConfigRemoteFeedbackFilter (ctre::phoenix::motorcontrol::can::BaseTalon &talonRef, int remoteOrdinal, int timeoutMs=0)
 Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. More...
 
virtual ctre::phoenix::ErrorCode ConfigSensorTerm (SensorTerm sensorTerm, FeedbackDevice feedbackDevice, int timeoutMs=0)
 Select what sensor term should be bound to switch feedback device. More...
 
virtual ctre::phoenix::ErrorCode ConfigSensorTerm (SensorTerm sensorTerm, RemoteFeedbackDevice feedbackDevice, int timeoutMs=0)
 Select what sensor term should be bound to switch feedback device. More...
 
virtual double GetSelectedSensorPosition (int pidIdx=0)
 Get the selected sensor position (in raw sensor units). More...
 
virtual double GetSelectedSensorVelocity (int pidIdx=0)
 Get the selected sensor velocity. More...
 
virtual ctre::phoenix::ErrorCode SetSelectedSensorPosition (double sensorPos, int pidIdx=0, int timeoutMs=50)
 Sets the sensor position to the given value. More...
 
virtual ctre::phoenix::ErrorCode SetControlFramePeriod (ControlFrame frame, int periodMs)
 Sets the period of the given control frame. More...
 
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod (StatusFrame frame, uint8_t periodMs, int timeoutMs=0)
 Sets the period of the given status frame. More...
 
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod (StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs=0)
 Sets the period of the given status frame. More...
 
virtual int GetStatusFramePeriod (StatusFrame frame, int timeoutMs=0)
 Gets the period of the given status frame. More...
 
virtual int GetStatusFramePeriod (StatusFrameEnhanced frame, int timeoutMs=0)
 Gets the period of the given status frame. More...
 
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod (ctre::phoenix::sensors::SensorVelocityMeasPeriod period, int timeoutMs=0)
 Sets the period over which velocity measurements are taken. More...
 
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod (VelocityMeasPeriod period, int timeoutMs=0)
 
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementWindow (int windowSize, int timeoutMs=0)
 Sets the number of velocity samples used in the rolling average velocity measurement. More...
 
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource (RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
 Configures the forward limit switch for a remote source. More...
 
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource (RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
 Configures the reverse limit switch for a remote source. More...
 
void OverrideLimitSwitchesEnable (bool enable)
 Sets the enable state for limit switches. More...
 
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource (LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
 Configures a limit switch for a local/remote source. More...
 
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource (LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
 Configures a limit switch for a local/remote source. More...
 
virtual ctre::phoenix::ErrorCode ConfigForwardSoftLimitThreshold (double forwardSensorLimit, int timeoutMs=0)
 Configures the forward soft limit threhold. More...
 
virtual ctre::phoenix::ErrorCode ConfigReverseSoftLimitThreshold (double reverseSensorLimit, int timeoutMs=0)
 Configures the reverse soft limit threshold. More...
 
virtual ctre::phoenix::ErrorCode ConfigForwardSoftLimitEnable (bool enable, int timeoutMs=0)
 Configures the forward soft limit enable. More...
 
virtual ctre::phoenix::ErrorCode ConfigReverseSoftLimitEnable (bool enable, int timeoutMs=0)
 Configures the reverse soft limit enable. More...
 
virtual void OverrideSoftLimitsEnable (bool enable)
 Can be used to override-disable the soft limits. More...
 
virtual ctre::phoenix::ErrorCode Config_kP (int slotIdx, double value, int timeoutMs=0)
 Sets the 'P' constant in the given parameter slot. More...
 
virtual ctre::phoenix::ErrorCode Config_kI (int slotIdx, double value, int timeoutMs=0)
 Sets the 'I' constant in the given parameter slot. More...
 
virtual ctre::phoenix::ErrorCode Config_kD (int slotIdx, double value, int timeoutMs=0)
 Sets the 'D' constant in the given parameter slot. More...
 
virtual ctre::phoenix::ErrorCode Config_kF (int slotIdx, double value, int timeoutMs=0)
 Sets the 'F' constant in the given parameter slot. More...
 
virtual ctre::phoenix::ErrorCode Config_IntegralZone (int slotIdx, double izone, int timeoutMs=0)
 Sets the Integral Zone constant in the given parameter slot. More...
 
virtual ctre::phoenix::ErrorCode ConfigAllowableClosedloopError (int slotIdx, double allowableCloseLoopError, int timeoutMs=0)
 Sets the allowable closed-loop error in the given parameter slot. More...
 
virtual ctre::phoenix::ErrorCode ConfigMaxIntegralAccumulator (int slotIdx, double iaccum, int timeoutMs=0)
 Sets the maximum integral accumulator in the given parameter slot. More...
 
virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeakOutput (int slotIdx, double percentOut, int timeoutMs=0)
 Sets the peak closed-loop output. More...
 
virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeriod (int slotIdx, int loopTimeMs, int timeoutMs=0)
 Sets the loop time (in milliseconds) of the PID closed-loop calculations. More...
 
virtual ctre::phoenix::ErrorCode ConfigAuxPIDPolarity (bool invert, int timeoutMs=0)
 Configures the Polarity of the Auxiliary PID (PID1). More...
 
ctre::phoenix::ErrorCode ConfigureSlot (const SlotConfiguration &slot, int slotIdx, int timeoutMs)
 Configures all slot persistant settings. More...
 
virtual ctre::phoenix::ErrorCode SetIntegralAccumulator (double iaccum, int pidIdx=0, int timeoutMs=0)
 Sets the integral accumulator. More...
 
virtual double GetClosedLoopError (int pidIdx=0)
 Gets the closed-loop error. More...
 
virtual double GetIntegralAccumulator (int pidIdx=0)
 Gets the iaccum value. More...
 
virtual double GetErrorDerivative (int pidIdx=0)
 Gets the derivative of the closed-loop error. More...
 
virtual ctre::phoenix::ErrorCode SelectProfileSlot (int slotIdx, int pidIdx)
 Selects which profile slot to use for closed-loop control. More...
 
virtual double GetClosedLoopTarget (int pidIdx=0)
 Gets the current target of a given closed loop. More...
 
virtual double GetActiveTrajectoryPosition (int pidIdx=0)
 Gets the active trajectory target position using MotionMagic/MotionProfile control modes. More...
 
virtual double GetActiveTrajectoryVelocity (int pidIdx=0)
 Gets the active trajectory target velocity using MotionMagic/MotionProfile control modes. More...
 
virtual double GetActiveTrajectoryArbFeedFwd (int pidIdx=0)
 Gets the active trajectory arbitrary feedforward using MotionMagic/MotionProfile control modes. More...
 
virtual ctre::phoenix::ErrorCode ConfigMotionCruiseVelocity (double sensorUnitsPer100ms, int timeoutMs=0)
 Sets the Motion Magic Cruise Velocity. More...
 
virtual ctre::phoenix::ErrorCode ConfigMotionAcceleration (double sensorUnitsPer100msPerSec, int timeoutMs=0)
 Sets the Motion Magic Acceleration. More...
 
virtual ctre::phoenix::ErrorCode ConfigMotionSCurveStrength (int curveStrength, int timeoutMs=0)
 Sets the Motion Magic S Curve Strength. More...
 
virtual ErrorCode ClearMotionProfileTrajectories ()
 Clear the buffered motion profile in both controller's RAM (bottom), and in the API (top). More...
 
virtual int GetMotionProfileTopLevelBufferCount ()
 Retrieve just the buffer count for the api-level (top) buffer. More...
 
virtual ctre::phoenix::ErrorCode PushMotionProfileTrajectory (const ctre::phoenix::motion::TrajectoryPoint &trajPt)
 Push another trajectory point into the top level buffer (which is emptied into the motor controller's bottom buffer as room allows). More...
 
virtual ctre::phoenix::ErrorCode StartMotionProfile (ctre::phoenix::motion::BufferedTrajectoryPointStream &stream, uint32_t minBufferedPts, ControlMode motionProfControlMode)
 Simple one-shot firing of a complete MP. More...
 
virtual bool IsMotionProfileFinished ()
 Determine if running MP is complete. More...
 
virtual bool IsMotionProfileTopLevelBufferFull ()
 Retrieve just the buffer full for the api-level (top) buffer. More...
 
virtual void ProcessMotionProfileBuffer ()
 This must be called periodically to funnel the trajectory points from the API's top level buffer to the controller's bottom level buffer. More...
 
virtual ctre::phoenix::ErrorCode GetMotionProfileStatus (ctre::phoenix::motion::MotionProfileStatus &statusToFill)
 Retrieve all status information. More...
 
virtual ctre::phoenix::ErrorCode ClearMotionProfileHasUnderrun (int timeoutMs=0)
 Clear the "Has Underrun" flag. More...
 
virtual ctre::phoenix::ErrorCode ChangeMotionControlFramePeriod (int periodMs)
 Calling application can opt to speed up the handshaking between the robot API and the controller to increase the download rate of the controller's Motion Profile. More...
 
virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryPeriod (int baseTrajDurationMs, int timeoutMs=0)
 When trajectory points are processed in the motion profile executer, the MPE determines how long to apply the active trajectory point by summing baseTrajDurationMs with the timeDur of the trajectory point (see TrajectoryPoint). More...
 
virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryInterpolationEnable (bool enable, int timeoutMs=0)
 When trajectory points are processed in the buffer, the motor controller can linearly interpolate additional trajectory points between the buffered points. More...
 
virtual ErrorCode ConfigFeedbackNotContinuous (bool feedbackNotContinuous, int timeoutMs=0)
 Disables continuous tracking of the position for analog and pulse-width. More...
 
virtual ErrorCode ConfigRemoteSensorClosedLoopDisableNeutralOnLOS (bool remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs=0)
 Disables going to neutral (brake/coast) when a remote sensor is no longer detected. More...
 
virtual ErrorCode ConfigClearPositionOnLimitF (bool clearPositionOnLimitF, int timeoutMs=0)
 Enables clearing the position of the feedback sensor when the forward limit switch is triggered. More...
 
virtual ErrorCode ConfigClearPositionOnLimitR (bool clearPositionOnLimitR, int timeoutMs=0)
 Enables clearing the position of the feedback sensor when the reverse limit switch is triggered. More...
 
virtual ErrorCode ConfigClearPositionOnQuadIdx (bool clearPositionOnQuadIdx, int timeoutMs=0)
 Enables clearing the position of the feedback sensor when the quadrature index signal is detected. More...
 
virtual ErrorCode ConfigLimitSwitchDisableNeutralOnLOS (bool limitSwitchDisableNeutralOnLOS, int timeoutMs=0)
 Disables limit switches triggering (if enabled) when the sensor is no longer detected. More...
 
virtual ErrorCode ConfigSoftLimitDisableNeutralOnLOS (bool softLimitDisableNeutralOnLOS, int timeoutMs=0)
 Disables soft limits triggering (if enabled) when the sensor is no longer detected. More...
 
virtual ErrorCode ConfigPulseWidthPeriod_EdgesPerRot (int pulseWidthPeriod_EdgesPerRot, int timeoutMs=0)
 Sets the edges per rotation of a pulse width sensor. More...
 
virtual ErrorCode ConfigPulseWidthPeriod_FilterWindowSz (int pulseWidthPeriod_FilterWindowSz, int timeoutMs=0)
 Sets the number of samples to use in smoothing a pulse width sensor with a rolling average. More...
 
virtual ctre::phoenix::ErrorCode GetLastError ()
 Gets the last error generated by this object. More...
 
virtual ctre::phoenix::ErrorCode GetFaults (Faults &toFill)
 Polls the various fault flags. More...
 
virtual ctre::phoenix::ErrorCode GetStickyFaults (StickyFaults &toFill)
 Polls the various sticky fault flags. More...
 
virtual ctre::phoenix::ErrorCode ClearStickyFaults (int timeoutMs=0)
 Clears all sticky faults. More...
 
virtual int GetFirmwareVersion ()
 Gets the firmware version of the device. More...
 
virtual bool HasResetOccurred ()
 Returns true if the device has reset since last call. More...
 
virtual ctre::phoenix::ErrorCode ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0)
 Sets the value of a custom parameter. More...
 
virtual int ConfigGetCustomParam (int paramIndex, int timeoutMs=0)
 Gets the value of a custom parameter. More...
 
virtual ctre::phoenix::ErrorCode ConfigSetParameter (ctre::phoenix::ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0)
 Sets a parameter. More...
 
virtual double ConfigGetParameter (ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0)
 Gets a parameter. More...
 
virtual ErrorCode ConfigGetParameter (ParamEnum param, int32_t valueToSend, int32_t &valueReceived, uint8_t &subValue, int32_t ordinal, int32_t timeoutMs)
 Gets a parameter by passing an int by reference. More...
 
virtual int GetBaseID ()
 
virtual ControlMode GetControlMode ()
 
void Follow (IMotorController &masterToFollow, ctre::phoenix::motorcontrol::FollowerType followerType)
 Set the control mode and output value so that this motor controller will follow another motor controller. More...
 
virtual void Follow (IMotorController &masterToFollow)
 Set the control mode and output value so that this motor controller will follow another motor controller. More...
 
virtual void ValueUpdated ()
 When master makes a device, this routine is called to signal the update. More...
 
void GetSlotConfigs (SlotConfiguration &slot, int slotIdx=0, int timeoutMs=50)
 Gets all slot persistant settings. More...
 
void GetFilterConfigs (FilterConfiguration &Filter, int ordinal=0, int timeoutMs=50)
 Gets all filter persistant settings. More...
 
void * GetHandle ()
 
- Public Member Functions inherited from ctre::phoenix::motorcontrol::IMotorController
virtual ~IMotorController ()
 
virtual void Set (ControlMode Mode, double demand)=0
 Sets the appropriate output on the talon, depending on the mode. More...
 
virtual void Set (ControlMode mode, double demand0, DemandType demand1Type, double demand1)=0
 
virtual void NeutralOutput ()=0
 Neutral the motor output by setting control mode to disabled. More...
 
virtual void SetNeutralMode (NeutralMode neutralMode)=0
 Sets the mode of operation during neutral throttle output. More...
 
virtual void SetSensorPhase (bool PhaseSensor)=0
 Sets the phase of the sensor. More...
 
virtual void SetInverted (bool invert)=0
 Inverts the hbridge output of the motor controller. More...
 
virtual void SetInverted (InvertType invertType)=0
 Inverts the hbridge output of the motor controller in relation to the master if present. More...
 
virtual bool GetInverted () const =0
 
virtual ErrorCode ConfigFactoryDefault (int timeout)=0
 Revert all configurations to factory default values. More...
 
virtual ErrorCode ConfigOpenloopRamp (double secondsFromNeutralToFull, int timeoutMs=0)=0
 Configures the open-loop ramp rate of throttle output. More...
 
virtual ErrorCode ConfigClosedloopRamp (double secondsFromNeutralToFull, int timeoutMs=0)=0
 Configures the closed-loop ramp rate of throttle output. More...
 
virtual ErrorCode ConfigPeakOutputForward (double percentOut, int timeoutMs=0)=0
 Configures the forward peak output percentage. More...
 
virtual ErrorCode ConfigPeakOutputReverse (double percentOut, int timeoutMs=0)=0
 Configures the reverse peak output percentage. More...
 
virtual ErrorCode ConfigNominalOutputForward (double percentOut, int timeoutMs=0)=0
 Configures the forward nominal output percentage. More...
 
virtual ErrorCode ConfigNominalOutputReverse (double percentOut, int timeoutMs=0)=0
 Configures the reverse nominal output percentage. More...
 
virtual ErrorCode ConfigNeutralDeadband (double percentDeadband, int timeoutMs=0)=0
 Configures the output deadband percentage. More...
 
virtual ErrorCode ConfigVoltageCompSaturation (double voltage, int timeoutMs=0)=0
 Configures the Voltage Compensation saturation voltage. More...
 
virtual ErrorCode ConfigVoltageMeasurementFilter (int filterWindowSamples, int timeoutMs=0)=0
 Configures the voltage measurement filter. More...
 
virtual void EnableVoltageCompensation (bool enable)=0
 Enables voltage compensation. More...
 
virtual bool IsVoltageCompensationEnabled ()=0
 Returns the enable state of Voltage Compensation that the caller has set. More...
 
virtual double GetBusVoltage ()=0
 Gets the bus voltage seen by the device. More...
 
virtual double GetMotorOutputPercent ()=0
 Gets the output percentage of the motor controller. More...
 
virtual double GetMotorOutputVoltage ()=0
 
virtual double GetTemperature ()=0
 Gets the temperature of the motor controller. More...
 
virtual ErrorCode ConfigSelectedFeedbackSensor (RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)=0
 Select the remote feedback device for the motor controller. More...
 
virtual ErrorCode ConfigSelectedFeedbackCoefficient (double coefficient, int pidIdx=0, int timeoutMs=0)=0
 The Feedback Coefficient is a scalar applied to the value of the feedback sensor. More...
 
virtual ErrorCode ConfigRemoteFeedbackFilter (int deviceID, RemoteSensorSource remoteSensorSource, int remoteOrdinal, int timeoutMs=0)=0
 Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. More...
 
virtual ErrorCode ConfigRemoteFeedbackFilter (ctre::phoenix::sensors::CANCoder &canCoderRef, int remoteOrdinal, int timeoutMs=0)=0
 Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. More...
 
virtual ErrorCode ConfigRemoteFeedbackFilter (ctre::phoenix::motorcontrol::can::BaseTalon &talonRef, int remoteOrdinal, int timeoutMs=0)=0
 Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. More...
 
virtual ErrorCode ConfigSensorTerm (SensorTerm sensorTerm, FeedbackDevice feedbackDevice, int timeoutMs=0)=0
 Select what sensor term should be bound to switch feedback device. More...
 
virtual double GetSelectedSensorPosition (int pidIdx=0)=0
 Get the selected sensor position (in raw sensor units). More...
 
virtual double GetSelectedSensorVelocity (int pidIdx=0)=0
 Get the selected sensor velocity. More...
 
virtual ErrorCode SetSelectedSensorPosition (double sensorPos, int pidIdx=0, int timeoutMs=50)=0
 Sets the sensor position to the given value. More...
 
virtual ErrorCode SetControlFramePeriod (ControlFrame frame, int periodMs)=0
 Sets the period of the given control frame. More...
 
virtual ErrorCode SetStatusFramePeriod (StatusFrame frame, uint8_t periodMs, int timeoutMs=0)=0
 Sets the period of the given status frame. More...
 
virtual int GetStatusFramePeriod (StatusFrame frame, int timeoutMs=0)=0
 Gets the period of the given status frame. More...
 
virtual ErrorCode ConfigForwardLimitSwitchSource (RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)=0
 Configures the forward limit switch for a remote source. More...
 
virtual ErrorCode ConfigReverseLimitSwitchSource (RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)=0
 Configures the reverse limit switch for a remote source. More...
 
virtual void OverrideLimitSwitchesEnable (bool enable)=0
 Sets the enable state for limit switches. More...
 
virtual ErrorCode ConfigForwardSoftLimitThreshold (double forwardSensorLimit, int timeoutMs=0)=0
 Configures the forward soft limit threhold. More...
 
virtual ErrorCode ConfigReverseSoftLimitThreshold (double reverseSensorLimit, int timeoutMs=0)=0
 Configures the reverse soft limit threshold. More...
 
virtual ErrorCode ConfigForwardSoftLimitEnable (bool enable, int timeoutMs=0)=0
 Configures the forward soft limit enable. More...
 
virtual ErrorCode ConfigReverseSoftLimitEnable (bool enable, int timeoutMs=0)=0
 Configures the reverse soft limit enable. More...
 
virtual void OverrideSoftLimitsEnable (bool enable)=0
 Can be used to override-disable the soft limits. More...
 
virtual ErrorCode Config_kP (int slotIdx, double value, int timeoutMs=0)=0
 Sets the 'P' constant in the given parameter slot. More...
 
virtual ErrorCode Config_kI (int slotIdx, double value, int timeoutMs=0)=0
 Sets the 'I' constant in the given parameter slot. More...
 
virtual ErrorCode Config_kD (int slotIdx, double value, int timeoutMs=0)=0
 Sets the 'D' constant in the given parameter slot. More...
 
virtual ErrorCode Config_kF (int slotIdx, double value, int timeoutMs=0)=0
 Sets the 'F' constant in the given parameter slot. More...
 
virtual ErrorCode Config_IntegralZone (int slotIdx, double izone, int timeoutMs=0)=0
 Sets the Integral Zone constant in the given parameter slot. More...
 
virtual ErrorCode ConfigAllowableClosedloopError (int slotIdx, double allowableCloseLoopError, int timeoutMs=0)=0
 Sets the allowable closed-loop error in the given parameter slot. More...
 
virtual ErrorCode ConfigMaxIntegralAccumulator (int slotIdx, double iaccum, int timeoutMs=0)=0
 Sets the maximum integral accumulator in the given parameter slot. More...
 
virtual ErrorCode ConfigClosedLoopPeakOutput (int slotIdx, double percentOut, int timeoutMs=0)=0
 Sets the peak closed-loop output. More...
 
virtual ErrorCode ConfigClosedLoopPeriod (int slotIdx, int loopTimeMs, int timeoutMs=0)=0
 Sets the loop time (in milliseconds) of the PID closed-loop calculations. More...
 
virtual ErrorCode ConfigAuxPIDPolarity (bool invert, int timeoutMs=0)=0
 Configures the Polarity of the Auxiliary PID (PID1). More...
 
virtual ErrorCode SetIntegralAccumulator (double iaccum, int pidIdx=0, int timeoutMs=0)=0
 Sets the integral accumulator. More...
 
virtual double GetClosedLoopError (int pidIdx=0)=0
 Gets the closed-loop error. More...
 
virtual double GetIntegralAccumulator (int pidIdx=0)=0
 Gets the iaccum value. More...
 
virtual double GetErrorDerivative (int pidIdx=0)=0
 Gets the derivative of the closed-loop error. More...
 
virtual ErrorCode SelectProfileSlot (int slotIdx, int pidIdx)=0
 Selects which profile slot to use for closed-loop control. More...
 
virtual double GetClosedLoopTarget (int pidIdx=0)=0
 Gets the current target of a given closed loop. More...
 
virtual double GetActiveTrajectoryPosition (int pidIdx=0)=0
 Gets the active trajectory target position for using MotionMagic/MotionProfile control modes. More...
 
virtual double GetActiveTrajectoryVelocity (int pidIdx=0)=0
 Gets the active trajectory target velocity for using MotionMagic/MotionProfile control modes. More...
 
virtual double GetActiveTrajectoryArbFeedFwd (int pidIdx=0)=0
 Gets the active trajectory arbitrary feedforward using MotionMagic/MotionProfile control modes. More...
 
virtual ErrorCode ConfigMotionCruiseVelocity (double sensorUnitsPer100ms, int timeoutMs=0)=0
 Sets the Motion Magic Cruise Velocity. More...
 
virtual ErrorCode ConfigMotionAcceleration (double sensorUnitsPer100msPerSec, int timeoutMs=0)=0
 Sets the Motion Magic Acceleration. More...
 
virtual ErrorCode ConfigMotionSCurveStrength (int curveStrength, int timeoutMs)=0
 Sets the Motion Magic S Curve Strength. More...
 
virtual ErrorCode ClearMotionProfileTrajectories ()=0
 Clear the buffered motion profile in both controller's RAM (bottom), and in the API (top). More...
 
virtual int GetMotionProfileTopLevelBufferCount ()=0
 Retrieve just the buffer count for the api-level (top) buffer. More...
 
virtual ErrorCode PushMotionProfileTrajectory (const ctre::phoenix::motion::TrajectoryPoint &trajPt)=0
 Push another trajectory point into the top level buffer (which is emptied into the motor controller's bottom buffer as room allows). More...
 
virtual bool IsMotionProfileTopLevelBufferFull ()=0
 Retrieve just the buffer full for the api-level (top) buffer. More...
 
virtual void ProcessMotionProfileBuffer ()=0
 This must be called periodically to funnel the trajectory points from the API's top level buffer to the controller's bottom level buffer. More...
 
virtual ErrorCode GetMotionProfileStatus (ctre::phoenix::motion::MotionProfileStatus &statusToFill)=0
 Retrieve all status information. More...
 
virtual ErrorCode ClearMotionProfileHasUnderrun (int timeoutMs=0)=0
 Clear the "Has Underrun" flag. More...
 
virtual ErrorCode ChangeMotionControlFramePeriod (int periodMs)=0
 Calling application can opt to speed up the handshaking between the robot API and the controller to increase the download rate of the controller's Motion Profile. More...
 
virtual ErrorCode ConfigMotionProfileTrajectoryPeriod (int baseTrajDurationMs, int timeoutMs=0)=0
 When trajectory points are processed in the motion profile executer, the MPE determines how long to apply the active trajectory point by summing baseTrajDurationMs with the timeDur of the trajectory point (see TrajectoryPoint). More...
 
virtual ErrorCode ConfigFeedbackNotContinuous (bool feedbackNotContinuous, int timeoutMs=0)=0
 Disables continuous tracking of the position for analog and pulse-width. More...
 
virtual ErrorCode ConfigRemoteSensorClosedLoopDisableNeutralOnLOS (bool remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs=0)=0
 Disables going to neutral (brake/coast) when a remote sensor is no longer detected. More...
 
virtual ErrorCode ConfigClearPositionOnLimitF (bool clearPositionOnLimitF, int timeoutMs=0)=0
 Enables clearing the position of the feedback sensor when the forward limit switch is triggered. More...
 
virtual ErrorCode ConfigClearPositionOnLimitR (bool clearPositionOnLimitR, int timeoutMs=0)=0
 Enables clearing the position of the feedback sensor when the reverse limit switch is triggered. More...
 
virtual ErrorCode ConfigClearPositionOnQuadIdx (bool clearPositionOnQuadIdx, int timeoutMs=0)=0
 Enables clearing the position of the feedback sensor when the quadrature index signal is detected. More...
 
virtual ErrorCode ConfigLimitSwitchDisableNeutralOnLOS (bool limitSwitchDisableNeutralOnLOS, int timeoutMs=0)=0
 Disables limit switches triggering (if enabled) when the sensor is no longer detected. More...
 
virtual ErrorCode ConfigSoftLimitDisableNeutralOnLOS (bool softLimitDisableNeutralOnLOS, int timeoutMs=0)=0
 Disables soft limits triggering (if enabled) when the sensor is no longer detected. More...
 
virtual ErrorCode ConfigPulseWidthPeriod_EdgesPerRot (int pulseWidthPeriod_EdgesPerRot, int timeoutMs=0)=0
 Sets the edges per rotation of a pulse width sensor. More...
 
virtual ErrorCode ConfigPulseWidthPeriod_FilterWindowSz (int pulseWidthPeriod_FilterWindowSz, int timeoutMs=0)=0
 Sets the number of samples to use in smoothing a pulse width sensor with a rolling average. More...
 
virtual ErrorCode GetLastError ()=0
 Gets the last error generated by this object. More...
 
virtual ErrorCode GetFaults (Faults &toFill)=0
 Polls the various fault flags. More...
 
virtual ErrorCode GetStickyFaults (StickyFaults &toFill)=0
 Polls the various sticky fault flags. More...
 
virtual ErrorCode ClearStickyFaults (int timeoutMs=0)=0
 Clears all sticky faults. More...
 
virtual int GetFirmwareVersion ()=0
 Gets the firmware version of the device. More...
 
virtual bool HasResetOccurred ()=0
 Returns true if the device has reset since last call. More...
 
virtual ErrorCode ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0)=0
 Sets the value of a custom parameter. More...
 
virtual int ConfigGetCustomParam (int paramIndex, int timeoutMs=0)=0
 Gets the value of a custom parameter. More...
 
virtual ErrorCode ConfigSetParameter (ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0)=0
 Sets a parameter. More...
 
virtual double ConfigGetParameter (ParamEnum paramEnum, int ordinal, int timeoutMs=0)=0
 Gets a parameter. More...
 
virtual int GetBaseID ()=0
 
virtual int GetDeviceID ()=0
 Returns the Device ID. More...
 
virtual ControlMode GetControlMode ()=0
 
- Public Member Functions inherited from ctre::phoenix::motorcontrol::IFollower
virtual ~IFollower ()
 
virtual void Follow (ctre::phoenix::motorcontrol::IMotorController &masterToFollow)=0
 Set the control mode and output value so that this motor controller will follow another motor controller. More...
 
virtual void ValueUpdated ()=0
 When master makes a device, this routine is called to signal the update. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from ctre::phoenix::motorcontrol::can::BaseMotorController
static void DestroyAllMotControllers ()
 Destructs all motor controller objects. More...
 
- Protected Member Functions inherited from ctre::phoenix::motorcontrol::can::BaseMotorController
ctre::phoenix::motorcontrol::VictorSPXSimCollectionGetVictorSPXSimCollection ()
 
virtual ctre::phoenix::ErrorCode BaseConfigAllSettings (const BaseMotorControllerConfiguration &allConfigs, int timeoutMs)
 Configures all base persistant settings. More...
 
virtual void BaseGetAllConfigs (BaseMotorControllerConfiguration &allConfigs, int timeoutMs)
 Gets all base persistant settings. More...
 
virtual void BaseGetPIDConfigs (BasePIDSetConfiguration &pid, int pidIdx, int timeoutMs)
 Gets all base PID set persistant settings. More...
 
virtual double GetOutputCurrent ()
 Gets the output current of the motor controller. More...
 

Detailed Description

VEX Victor SPX Motor Controller when used on CAN Bus.


// Example usage of a VictorSPX motor controller
VictorSPX motor{0}; // creates a new VictorSPX with ID 0

motor.Set(VictorSPXControlMode::PercentOutput, 0.5); // runs the motor at 50% power

std::cout << motor.GetMotorOutputPercent() << std::endl; // prints the percent output of the motor (0.5)
std::cout << motor.GetBusVoltage() << std::endl; // prints the bus voltage seen by the motor controller

ErrorCode error = motor.GetLastError(); // gets the last error generated by the motor controller
Faults faults;
ErrorCode faultsError = motor.GetFaults(faults); // fills faults with the current motor controller faults; returns the last error generated

Constructor & Destructor Documentation

◆ VictorSPX() [1/3]

ctre::phoenix::motorcontrol::can::VictorSPX::VictorSPX ( int  deviceNumber)

Constructor.

Parameters
deviceNumber[0,62]

◆ VictorSPX() [2/3]

ctre::phoenix::motorcontrol::can::VictorSPX::VictorSPX ( int  deviceNumber,
std::string const &  canbus 
)

Constructor so non-FRC platforms can specify a CAN 2.0 socketcan bus.

Parameters
deviceNumberCAN Device ID of VictorSPX
canbusString specifying the bus

◆ ~VictorSPX()

virtual ctre::phoenix::motorcontrol::can::VictorSPX::~VictorSPX ( )
inlinevirtual

◆ VictorSPX() [3/3]

ctre::phoenix::motorcontrol::can::VictorSPX::VictorSPX ( VictorSPX const &  )
delete

Member Function Documentation

◆ ConfigAllSettings()

virtual ctre::phoenix::ErrorCode ctre::phoenix::motorcontrol::can::VictorSPX::ConfigAllSettings ( const VictorSPXConfiguration allConfigs,
int  timeoutMs = 50 
)
virtual

Configures all persistent settings.

Parameters
allConfigsObject with all of the persistant settings
timeoutMsTimeout 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.

◆ GetAllConfigs()

virtual void ctre::phoenix::motorcontrol::can::VictorSPX::GetAllConfigs ( VictorSPXConfiguration allConfigs,
int  timeoutMs = 50 
)
virtual

Gets all persistant settings.

Parameters
allConfigsObject with all of the persistant settings
timeoutMsTimeout 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()

void ctre::phoenix::motorcontrol::can::VictorSPX::GetPIDConfigs ( VictorSPXPIDSetConfiguration pid,
int  pidIdx = 0,
int  timeoutMs = 50 
)

Gets all PID set persistant settings.

Parameters
pidObject with all of the PID set persistant settings
pidIdx0 for Primary closed-loop. 1 for auxiliary closed-loop.
timeoutMsTimeout 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.

◆ GetSimCollection()

ctre::phoenix::motorcontrol::VictorSPXSimCollection & ctre::phoenix::motorcontrol::can::VictorSPX::GetSimCollection ( )
Returns
object that can set simulation inputs.

◆ operator=()

VictorSPX & ctre::phoenix::motorcontrol::can::VictorSPX::operator= ( VictorSPX const &  )
delete

◆ Set() [1/4]

virtual void ctre::phoenix::motorcontrol::can::VictorSPX::Set ( ctre::phoenix::motorcontrol::ControlMode  mode,
double  demand0,
ctre::phoenix::motorcontrol::DemandType  demand1Type,
double  demand1 
)
virtual
Parameters
modeSets the appropriate output on the talon, depending on the mode.
demand0The 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.
demand1TypeThe 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.
demand1Supplmental output value. AuxPID: Target position in Sensor Units ArbitraryFeedForward: Percent Output between -1.0 and 1.0

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);

Reimplemented from ctre::phoenix::motorcontrol::can::BaseMotorController.

Reimplemented in ctre::phoenix::motorcontrol::can::WPI_VictorSPX.

◆ Set() [2/4]

virtual void ctre::phoenix::motorcontrol::can::VictorSPX::Set ( ctre::phoenix::motorcontrol::ControlMode  mode,
double  value 
)
virtual

Sets the appropriate output on the talon, depending on the mode.

Parameters
modeThe 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.
valueThe setpoint value, as described above.

Standard Driving Example: _talonLeft.set(ControlMode.PercentOutput, leftJoy); _talonRght.set(ControlMode.PercentOutput, rghtJoy);

Reimplemented from ctre::phoenix::motorcontrol::can::BaseMotorController.

Reimplemented in ctre::phoenix::motorcontrol::can::WPI_VictorSPX.

◆ Set() [3/4]

void ctre::phoenix::motorcontrol::can::VictorSPX::Set ( ctre::phoenix::motorcontrol::VictorSPXControlMode  mode,
double  demand0,
ctre::phoenix::motorcontrol::DemandType  demand1Type,
double  demand1 
)
Parameters
modeSets the appropriate output on the motor controller, depending on the mode.
demand0The 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.
demand1TypeThe 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.
demand1Supplmental 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);

◆ Set() [4/4]

void ctre::phoenix::motorcontrol::can::VictorSPX::Set ( ctre::phoenix::motorcontrol::VictorSPXControlMode  mode,
double  value 
)

Sets the appropriate output on the motor controller, depending on the mode.

Parameters
modeThe 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.
valueThe setpoint value, as described above.

Standard Driving Example: victorLeft.set(ControlMode.PercentOutput, leftJoy); victorRght.set(ControlMode.PercentOutput, rghtJoy);


The documentation for this class was generated from the following file: