31 namespace motorcontrol {
34 class MotControllerWithBuffer_LowLevel;
35 class MotController_LowLevel;
43 namespace motorcontrol {
74 std::string
toString(
const std::string& prependString) {
112 std::string retstr = prependString +
".remoteSensorDeviceID = " + std::to_string(
remoteSensorDeviceID) +
";\n";
231 std::string retstr = prependString +
".kP = " + std::to_string(
kP) +
";\n";
232 retstr += prependString +
".kI = " + std::to_string(
kI) +
";\n";
233 retstr += prependString +
".kD = " + std::to_string(
kD) +
";\n";
234 retstr += prependString +
".kF = " + std::to_string(
kF) +
";\n";
235 retstr += prependString +
".integralZone = " + std::to_string(
integralZone) +
";\n";
238 retstr += prependString +
".closedLoopPeakOutput = " + std::to_string(
closedLoopPeakOutput) +
";\n";
239 retstr += prependString +
".closedLoopPeriod = " + std::to_string(
closedLoopPeriod) +
";\n";
485 std::string retstr = prependString +
".openloopRamp = " + std::to_string(
openloopRamp) +
";\n";
486 retstr += prependString +
".closedloopRamp = " + std::to_string(
closedloopRamp) +
";\n";
487 retstr += prependString +
".peakOutputForward = " + std::to_string(
peakOutputForward) +
";\n";
488 retstr += prependString +
".peakOutputReverse = " + std::to_string(
peakOutputReverse) +
";\n";
489 retstr += prependString +
".nominalOutputForward = " + std::to_string(
nominalOutputForward) +
";\n";
490 retstr += prependString +
".nominalOutputReverse = " + std::to_string(
nominalOutputReverse) +
";\n";
491 retstr += prependString +
".neutralDeadband = " + std::to_string(
neutralDeadband) +
";\n";
492 retstr += prependString +
".voltageCompSaturation = " + std::to_string(
voltageCompSaturation) +
";\n";
504 retstr += prependString +
".auxPIDPolarity = " + std::to_string(
auxPIDPolarity) +
";\n";
507 retstr += prependString +
".motionCruiseVelocity = " + std::to_string(
motionCruiseVelocity) +
";\n";
508 retstr += prependString +
".motionAcceleration = " + std::to_string(
motionAcceleration) +
";\n";
509 retstr += prependString +
".motionCurveStrength = " + std::to_string(
motionCurveStrength) +
";\n";
511 retstr += prependString +
".feedbackNotContinuous = " + std::to_string(
feedbackNotContinuous) +
";\n";
513 retstr += prependString +
".clearPositionOnLimitF = " + std::to_string(
clearPositionOnLimitF) +
";\n";
514 retstr += prependString +
".clearPositionOnLimitR = " + std::to_string(
clearPositionOnLimitR) +
";\n";
583 double m_setPoint = 0;
594 bool _isVcompEn =
false;
998 FeedbackDevice feedbackDevice,
int pidIdx = 0,
int timeoutMs = 0);
1019 double coefficient,
int pidIdx = 0,
int timeoutMs = 0);
1038 [[deprecated(
"This device's Phoenix 5 API is deprecated for removal in the 2025 season."
1039 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
1040 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
1060 [[deprecated(
"This device's Phoenix 5 API is deprecated for removal in the 2025 season."
1061 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
1062 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
1202 uint8_t periodMs,
int timeoutMs = 0);
1243 [[deprecated(
"Use the overload with SensorVelocityMeasPeriod instead.")]]
1284 int deviceID,
int timeoutMs = 0);
1306 int deviceID,
int timeoutMs = 0);
1532 double allowableCloseLoopError,
int timeoutMs = 0);
2190 uint8_t subValue,
int ordinal,
int timeoutMs = 0);
2225 int32_t& valueReceived, uint8_t& subValue, int32_t ordinal,
Stream of trajectory points for Talon/Victor motion profiling.
Definition: BufferedTrajectoryPointStream.h:13
Interface for motor controllers.
Definition: IMotorController.h:35
static std::string toString(RemoteSensorSource value)
Get string representation of specified remote sensor source.
Definition: RemoteSensorSource.h:101
Collection of simulation commands available to a VictorSPX motor controller.
Definition: VictorSPXSimCollection.h:26
Base motor controller features for all CTRE CAN motor controllers.
Definition: BaseMotorController.h:578
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementWindow(int windowSize, int timeoutMs=0)
Sets the number of velocity samples used in the rolling average velocity measurement.
virtual void NeutralOutput()
Neutral the motor output by setting control mode to disabled.
virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeakOutput(int slotIdx, double percentOut, int timeoutMs=0)
Sets the peak closed-loop output.
virtual ctre::phoenix::ErrorCode ChangeMotionControlFramePeriod(int periodMs)
Calling application can opt to speed up the handshaking between the robot API and the controller to i...
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.
virtual ErrorCode ConfigClearPositionOnQuadIdx(bool clearPositionOnQuadIdx, int timeoutMs=0)
Enables clearing the position of the feedback sensor when the quadrature index signal is detected.
ctre::phoenix::ErrorCode ConfigureSlot(const SlotConfiguration &slot, int slotIdx, int timeoutMs)
Configures all slot persistant settings.
virtual ctre::phoenix::ErrorCode SelectProfileSlot(int slotIdx, int pidIdx)
Selects which profile slot to use for closed-loop control.
virtual ctre::phoenix::ErrorCode ClearStickyFaults(int timeoutMs=0)
Clears all sticky faults.
virtual void EnableVoltageCompensation(bool enable)
Enables voltage compensation.
virtual ErrorCode ConfigLimitSwitchDisableNeutralOnLOS(bool limitSwitchDisableNeutralOnLOS, int timeoutMs=0)
Disables limit switches triggering (if enabled) when the sensor is no longer detected.
virtual ctre::phoenix::ErrorCode ConfigVoltageMeasurementFilter(int filterWindowSamples, int timeoutMs=0)
Configures the voltage measurement filter.
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.
virtual void OverrideSoftLimitsEnable(bool enable)
Can be used to override-disable the soft limits.
virtual double GetSelectedSensorPosition(int pidIdx=0)
Get the selected sensor position (in raw sensor units).
virtual ctre::phoenix::ErrorCode ConfigSensorTerm(SensorTerm sensorTerm, FeedbackDevice feedbackDevice, int timeoutMs=0)
Select what sensor term should be bound to switch feedback device.
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.
virtual ctre::phoenix::ErrorCode Config_kP(int slotIdx, double value, int timeoutMs=0)
Sets the 'P' constant in the given parameter slot.
virtual double GetIntegralAccumulator(int pidIdx=0)
Gets the iaccum value.
virtual ctre::phoenix::ErrorCode ConfigReverseSoftLimitEnable(bool enable, int timeoutMs=0)
Configures the reverse soft limit enable.
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the remote feedback device for the motor controller.
virtual bool IsVoltageCompensationEnabled()
Returns the enable state of Voltage Compensation that the caller has set.
virtual ctre::phoenix::ErrorCode BaseConfigAllSettings(const BaseMotorControllerConfiguration &allConfigs, int timeoutMs)
Configures all base persistant settings.
virtual ctre::phoenix::ErrorCode ConfigAllowableClosedloopError(int slotIdx, double allowableCloseLoopError, int timeoutMs=0)
Sets the allowable closed-loop error in the given parameter slot.
virtual ErrorCode ConfigPulseWidthPeriod_EdgesPerRot(int pulseWidthPeriod_EdgesPerRot, int timeoutMs=0)
Sets the edges per rotation of a pulse width sensor.
virtual void SetInverted(bool invert)
Inverts the hbridge output of the motor controller.
virtual double GetSelectedSensorVelocity(int pidIdx=0)
Get the selected sensor velocity.
virtual double GetMotorOutputPercent()
Gets the output percentage of the motor controller.
virtual ctre::phoenix::ErrorCode Config_kI(int slotIdx, double value, int timeoutMs=0)
Sets the 'I' constant in the given parameter slot.
virtual ErrorCode ConfigFeedbackNotContinuous(bool feedbackNotContinuous, int timeoutMs=0)
Disables continuous tracking of the position for analog and pulse-width.
virtual ctre::phoenix::ErrorCode ConfigMotionCruiseVelocity(double sensorUnitsPer100ms, int timeoutMs=0)
Sets the Motion Magic Cruise Velocity.
virtual double GetTemperature()
Gets the temperature of the motor controller.
virtual double GetClosedLoopTarget(int pidIdx=0)
Gets the current target of a given closed loop.
virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeriod(int slotIdx, int loopTimeMs, int timeoutMs=0)
Sets the loop time (in milliseconds) of the PID closed-loop calculations.
virtual ErrorCode ConfigSoftLimitDisableNeutralOnLOS(bool softLimitDisableNeutralOnLOS, int timeoutMs=0)
Disables soft limits triggering (if enabled) when the sensor is no longer detected.
virtual int GetFirmwareVersion()
Gets the firmware version of the device.
virtual double GetBusVoltage()
Gets the bus voltage seen by the device.
virtual ErrorCode ConfigClearPositionOnLimitR(bool clearPositionOnLimitR, int timeoutMs=0)
Enables clearing the position of the feedback sensor when the reverse limit switch is triggered.
virtual ctre::phoenix::ErrorCode ConfigForwardSoftLimitThreshold(double forwardSensorLimit, int timeoutMs=0)
Configures the forward soft limit threhold.
virtual void SetNeutralMode(NeutralMode neutralMode)
Sets the mode of operation during neutral throttle output.
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...
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the feedback device for the motor controller.
virtual ctre::phoenix::ErrorCode ConfigMotionSCurveStrength(int curveStrength, int timeoutMs=0)
Sets the Motion Magic S Curve Strength.
virtual ctre::phoenix::ErrorCode Config_kF(int slotIdx, double value, int timeoutMs=0)
Sets the 'F' constant in the given parameter slot.
virtual ctre::phoenix::ErrorCode ClearMotionProfileHasUnderrun(int timeoutMs=0)
Clear the "Has Underrun" flag.
virtual ctre::phoenix::ErrorCode ConfigMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs=0)
Sets the maximum integral accumulator in the given parameter slot.
virtual ctre::phoenix::ErrorCode ConfigNeutralDeadband(double percentDeadband, int timeoutMs=0)
Configures the output deadband percentage.
virtual double GetClosedLoopError(int pidIdx=0)
Gets the closed-loop error.
virtual ctre::phoenix::ErrorCode ConfigFactoryDefault(int timeoutMs=50)
Revert all configurations to factory default values.
virtual ErrorCode ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(bool remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs=0)
Disables going to neutral (brake/coast) when a remote sensor is no longer detected.
virtual double GetActiveTrajectoryVelocity(int pidIdx=0)
Gets the active trajectory target velocity using MotionMagic/MotionProfile control modes.
virtual void SetSensorPhase(bool PhaseSensor)
Sets the phase of the sensor.
virtual int GetDeviceID()
Returns the Device ID.
virtual double GetOutputCurrent()
Gets the output current of the motor controller.
BaseMotorController & operator=(BaseMotorController const &)=delete
virtual ctre::phoenix::ErrorCode ConfigNominalOutputForward(double percentOut, int timeoutMs=0)
Configures the forward nominal output percentage.
static void DestroyAllMotControllers()
Destructs all motor controller objects.
virtual ctre::phoenix::ErrorCode ConfigNominalOutputReverse(double percentOut, int timeoutMs=0)
Configures the reverse nominal output percentage.
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 control...
virtual void BaseGetPIDConfigs(BasePIDSetConfiguration &pid, int pidIdx, int timeoutMs)
Gets all base PID set persistant settings.
virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs=0)
Gets the period of the given status frame.
virtual ctre::phoenix::ErrorCode ConfigPeakOutputForward(double percentOut, int timeoutMs=0)
Configures the forward peak output percentage.
virtual ctre::phoenix::ErrorCode StartMotionProfile(ctre::phoenix::motion::BufferedTrajectoryPointStream &stream, uint32_t minBufferedPts, ControlMode motionProfControlMode)
Simple one-shot firing of a complete MP.
virtual ctre::phoenix::ErrorCode ConfigReverseSoftLimitThreshold(double reverseSensorLimit, int timeoutMs=0)
Configures the reverse soft limit threshold.
virtual ctre::phoenix::ErrorCode ConfigPeakOutputReverse(double percentOut, int timeoutMs=0)
Configures the reverse peak output percentage.
virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1)
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.
virtual ctre::phoenix::ErrorCode ConfigAuxPIDPolarity(bool invert, int timeoutMs=0)
Configures the Polarity of the Auxiliary PID (PID1).
virtual bool IsMotionProfileTopLevelBufferFull()
Retrieve just the buffer full for the api-level (top) buffer.
virtual ErrorCode ConfigClearPositionOnLimitF(bool clearPositionOnLimitF, int timeoutMs=0)
Enables clearing the position of the feedback sensor when the forward limit switch is triggered.
virtual ctre::phoenix::ErrorCode ConfigClosedloopRamp(double secondsFromNeutralToFull, int timeoutMs=0)
Configures the closed-loop ramp rate of throttle output.
virtual void SetInverted(InvertType invertType)
Inverts the hbridge output of the motor controller in relation to the master if present.
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrame frame, uint8_t periodMs, int timeoutMs=0)
Sets the period of the given status frame.
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.
virtual double ConfigGetParameter(ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0)
Gets a parameter.
virtual bool GetInverted() const
virtual int ConfigGetCustomParam(int paramIndex, int timeoutMs=0)
Gets the value of a custom parameter.
void GetFilterConfigs(FilterConfiguration &Filter, int ordinal=0, int timeoutMs=50)
Gets all filter persistant settings.
virtual ctre::phoenix::ErrorCode ConfigSensorTerm(SensorTerm sensorTerm, RemoteFeedbackDevice feedbackDevice, int timeoutMs=0)
Select what sensor term should be bound to switch feedback device.
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
Configures a limit switch for a local/remote source.
BaseMotorController()=delete
virtual ControlMode GetControlMode()
virtual ctre::phoenix::ErrorCode GetLastError()
Gets the last error generated by this object.
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs=0)
Sets the period of the given status frame.
virtual bool IsMotionProfileFinished()
Determine if running MP is complete.
virtual ctre::phoenix::ErrorCode ConfigSetCustomParam(int newValue, int paramIndex, int timeoutMs=0)
Sets the value of a custom parameter.
virtual ctre::phoenix::ErrorCode GetMotionProfileStatus(ctre::phoenix::motion::MotionProfileStatus &statusToFill)
Retrieve all status information.
virtual ctre::phoenix::ErrorCode ConfigMotionAcceleration(double sensorUnitsPer100msPerSec, int timeoutMs=0)
Sets the Motion Magic Acceleration.
virtual void BaseGetAllConfigs(BaseMotorControllerConfiguration &allConfigs, int timeoutMs)
Gets all base persistant settings.
virtual void Follow(IMotorController &masterToFollow)
Set the control mode and output value so that this motor controller will follow another motor control...
void GetSlotConfigs(SlotConfiguration &slot, int slotIdx=0, int timeoutMs=50)
Gets all slot persistant settings.
virtual ctre::phoenix::ErrorCode SetIntegralAccumulator(double iaccum, int pidIdx=0, int timeoutMs=0)
Sets the integral accumulator.
virtual void ValueUpdated()
When master makes a device, this routine is called to signal the update.
virtual ctre::phoenix::ErrorCode ConfigOpenloopRamp(double secondsFromNeutralToFull, int timeoutMs=0)
Configures the open-loop ramp rate of throttle output.
virtual ctre::phoenix::ErrorCode GetFaults(Faults &toFill)
Polls the various fault flags.
virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryInterpolationEnable(bool enable, int timeoutMs=0)
When trajectory points are processed in the buffer, the motor controller can linearly interpolate add...
virtual ctre::phoenix::ErrorCode ConfigForwardSoftLimitEnable(bool enable, int timeoutMs=0)
Configures the forward soft limit enable.
virtual ctre::phoenix::ErrorCode ConfigSetParameter(ctre::phoenix::ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0)
Sets a parameter.
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
Configures the reverse limit switch for a remote source.
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.
virtual ErrorCode ClearMotionProfileTrajectories()
Clear the buffered motion profile in both controller's RAM (bottom), and in the API (top).
virtual ctre::phoenix::ErrorCode ConfigVoltageCompSaturation(double voltage, int timeoutMs=0)
Configures the Voltage Compensation saturation voltage.
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 a...
virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs=0)
Gets the period of the given status frame.
virtual double GetActiveTrajectoryArbFeedFwd(int pidIdx=0)
Gets the active trajectory arbitrary feedforward using MotionMagic/MotionProfile control modes.
virtual int GetMotionProfileTopLevelBufferCount()
Retrieve just the buffer count for the api-level (top) buffer.
virtual ~BaseMotorController()
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs=0)
ctre::phoenix::motorcontrol::VictorSPXSimCollection & GetVictorSPXSimCollection()
Definition: BaseMotorController.h:599
virtual bool HasResetOccurred()
Returns true if the device has reset since last call.
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
Configures the forward limit switch for a remote source.
BaseMotorController(BaseMotorController const &)=delete
virtual ctre::phoenix::ErrorCode Config_IntegralZone(int slotIdx, double izone, int timeoutMs=0)
Sets the Integral Zone constant in the given parameter slot.
virtual ctre::phoenix::ErrorCode GetStickyFaults(StickyFaults &toFill)
Polls the various sticky fault flags.
virtual ctre::phoenix::ErrorCode SetControlFramePeriod(ControlFrame frame, int periodMs)
Sets the period of the given control frame.
virtual void ProcessMotionProfileBuffer()
This must be called periodically to funnel the trajectory points from the API's top level buffer to t...
virtual double GetActiveTrajectoryPosition(int pidIdx=0)
Gets the active trajectory target position using MotionMagic/MotionProfile control modes.
virtual ctre::phoenix::ErrorCode Config_kD(int slotIdx, double value, int timeoutMs=0)
Sets the 'D' constant in the given parameter slot.
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(ctre::phoenix::sensors::SensorVelocityMeasPeriod period, int timeoutMs=0)
Sets the period over which velocity measurements are taken.
void OverrideLimitSwitchesEnable(bool enable)
Sets the enable state for limit switches.
virtual double GetMotorOutputVoltage()
virtual void Set(ControlMode mode, double value)
Sets the appropriate output on the talon, depending on the mode.
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
Configures a limit switch for a local/remote source.
BaseMotorController(int deviceNumber, const char *model, std::string const &canbus="")
Constructor for motor controllers.
virtual double GetErrorDerivative(int pidIdx=0)
Gets the derivative of the closed-loop error.
virtual ctre::phoenix::ErrorCode SetSelectedSensorPosition(double sensorPos, int pidIdx=0, int timeoutMs=50)
Sets the sensor position to the given value.
Util class to help with Base Motor Controller configs.
Definition: BaseMotorController.h:533
static bool PeakOutputReverseDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:546
static bool ClearPositionOnLimitFDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:565
static bool ReverseSoftLimitEnableDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:557
static bool ForwardSoftLimitThresholdDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:554
static bool VoltageCompSaturationDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:550
static bool VoltageMeasurementFilterDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:551
static bool MotionCruiseVelocityDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:559
static bool MotionAccelerationDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:560
static bool PulseWidthPeriod_FilterWindowSzDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:571
static bool OpenloopRampDifferent(const BaseMotorControllerConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseMotorController.h:543
static bool AuxPIDPolarityDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:558
static bool FeedbackNotContinuousDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:563
static bool TrajectoryInterpolationEnableDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:572
static bool PeakOutputForwardDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:545
static bool VelocityMeasurementWindowDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:553
static bool MotionProfileTrajectoryPeriodDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:562
static bool ClosedloopRampDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:544
static bool ReverseSoftLimitThresholdDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:555
static bool NominalOutputReverseDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:548
static bool NeutralDeadbandDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:549
static bool MotionSCurveStrength(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:561
static bool ForwardSoftLimitEnableDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:556
static bool PulseWidthPeriod_EdgesPerRotDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:570
static bool RemoteSensorClosedLoopDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:564
static bool ClearPositionOnLimitRDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:566
static bool SoftLimitDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:569
static bool VelocityMeasurementPeriodDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:552
static bool ClearPositionOnQuadIdxDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:567
static bool NominalOutputForwardDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:547
static bool LimitSwitchDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:568
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: BaseTalon.h:267
Util Class to help with slot configs.
Definition: BaseMotorController.h:250
static bool KPDifferent(const SlotConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseMotorController.h:260
static bool KFDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:263
static bool ClosedLoopPeriodDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:268
static bool KDDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:262
static bool MaxIntegralAccumulatorDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:266
static bool KIDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:261
static bool ClosedLoopPeakOutputDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:267
static bool IntegralZoneDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:264
static bool AllowableClosedloopErrorDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:265
CTRE CANCoder.
Definition: CANCoder.h:233
static std::string toString(SensorVelocityMeasPeriod value)
String representation of specified CANCoderVelocityMeasPeriod.
Definition: SensorVelocityMeasPeriod.h:58
ControlMode
Choose the control mode for a motor controller.
Definition: ControlMode.h:11
@ PercentOutput
Percent output [-1,1].
FollowerType
Choose the type of follower.
Definition: FollowerType.h:11
DemandType
How to interpret a demand value.
Definition: DemandType.h:10
InvertType
Choose the invert type of the motor controller.
Definition: InvertType.h:14
@ None
Same as SetInverted(false)
StatusFrameEnhanced
The different status frames available to enhanced motor controllers.
Definition: StatusFrame.h:11
SensorTerm
Choose the sensor term for a motor controller.
Definition: SensorTerm.h:11
LimitSwitchNormal
Choose whether the limit switch is normally open or normally closed.
Definition: LimitSwitchType.h:62
RemoteSensorSource
Choose the remote sensor source for a motor controller.
Definition: RemoteSensorSource.h:13
@ RemoteSensorSource_Off
Don't use a sensor.
RemoteFeedbackDevice
Choose the remote feedback device for a motor controller.
Definition: FeedbackDevice.h:179
RemoteLimitSwitchSource
Remote Limit switch source enum.
Definition: LimitSwitchType.h:35
FeedbackDevice
Choose the feedback device for a motor controller.
Definition: FeedbackDevice.h:14
NeutralMode
Choose the neutral mode for a motor controller.
Definition: NeutralMode.h:11
ControlFrame
Control Frames for motor controllers.
Definition: ControlFrame.h:11
VelocityMeasPeriod
Velocity Measurement Periods.
Definition: VelocityMeasPeriod.h:13
@ Period_100Ms
100ms measurement period
Definition: VelocityMeasPeriod.h:45
StatusFrame
The different status frames available to motor controllers.
Definition: StatusFrame.h:99
LimitSwitchSource
Limit switch source enum.
Definition: LimitSwitchType.h:11
SensorVelocityMeasPeriod
Enumerate filter periods for any sensor that measures velocity.
Definition: SensorVelocityMeasPeriod.h:13
ParamEnum
Signal enumeration for generic signal access.
Definition: paramEnum.h:13
ErrorCode
Definition: ErrorCode.h:13
namespace ctre
Definition: paramEnum.h:5
Util class to help custom configs.
Definition: CustomParamConfiguration.h:53
Configurables for any custom param configs.
Definition: CustomParamConfiguration.h:11
bool enableOptimizations
Enable optimizations for ConfigAll (defaults true)
Definition: CustomParamConfiguration.h:23
std::string toString()
Definition: CustomParamConfiguration.h:34
Motion Profile Status This is simply a data transer object.
Definition: MotionProfileStatus.h:15
Motion Profile Trajectory Point This is simply a data transfer object.
Definition: TrajectoryPoint.h:11
All the faults available to motor controllers.
Definition: Faults.h:11
All the sticky faults available to motor controllers.
Definition: StickyFaults.h:11
Configurables available to base motor controllers.
Definition: BaseMotorController.h:276
double motionCruiseVelocity
Motion Magic cruise velocity in raw sensor units per 100 ms.
Definition: BaseMotorController.h:379
int motionCurveStrength
Zero to use trapezoidal motion during motion magic.
Definition: BaseMotorController.h:387
bool auxPIDPolarity
PID polarity inversion.
Definition: BaseMotorController.h:367
bool clearPositionOnQuadIdx
Clear the position on index.
Definition: BaseMotorController.h:414
double motionAcceleration
Motion Magic acceleration in (raw sensor units per 100 ms) per second.
Definition: BaseMotorController.h:383
SlotConfiguration slot3
Configuration for slot 3.
Definition: BaseMotorController.h:355
bool clearPositionOnLimitR
Clear the position on reverse limit.
Definition: BaseMotorController.h:410
double nominalOutputReverse
Nominal/Minimum output in reverse direction [-1,0].
Definition: BaseMotorController.h:300
double openloopRamp
Seconds to go from 0 to full in open loop.
Definition: BaseMotorController.h:280
int pulseWidthPeriod_FilterWindowSz
Desired window size for a tachometer sensor.
Definition: BaseMotorController.h:430
double voltageCompSaturation
This is the max voltage to apply to the hbridge when voltage compensation is enabled.
Definition: BaseMotorController.h:311
double neutralDeadband
Neutral deadband [0.001, 0.25].
Definition: BaseMotorController.h:304
bool remoteSensorClosedLoopDisableNeutralOnLOS
Disable neutral'ing the motor when remote sensor is lost on CAN bus.
Definition: BaseMotorController.h:402
double closedloopRamp
Seconds to go from 0 to full in closed loop.
Definition: BaseMotorController.h:284
double reverseSoftLimitThreshold
Threshold for soft limits in reverse direction (in raw sensor units)
Definition: BaseMotorController.h:331
int pulseWidthPeriod_EdgesPerRot
Number of edges per rotation for a tachometer sensor.
Definition: BaseMotorController.h:426
bool softLimitDisableNeutralOnLOS
Disable neutral'ing the motor when remote soft limit is lost on CAN bus.
Definition: BaseMotorController.h:422
std::string toString(std::string prependString)
Definition: BaseMotorController.h:483
double peakOutputForward
Peak output in forward direction [0,1].
Definition: BaseMotorController.h:288
int velocityMeasurementWindow
Desired window for velocity measurement.
Definition: BaseMotorController.h:323
bool forwardSoftLimitEnable
Enable forward soft limit.
Definition: BaseMotorController.h:335
SlotConfiguration slot0
Configuration for slot 0.
Definition: BaseMotorController.h:343
int motionProfileTrajectoryPeriod
Motion profile base trajectory period in milliseconds.
Definition: BaseMotorController.h:394
bool feedbackNotContinuous
Determine whether feedback sensor is continuous or not.
Definition: BaseMotorController.h:398
FilterConfiguration remoteFilter1
Configuration for RemoteFilter 1.
Definition: BaseMotorController.h:375
int voltageMeasurementFilter
Number of samples in rolling average for voltage.
Definition: BaseMotorController.h:315
bool trajectoryInterpolationEnable
Enable motion profile trajectory point interpolation (defaults to true).
Definition: BaseMotorController.h:434
SlotConfiguration slot2
Configuration for slot 2.
Definition: BaseMotorController.h:351
ctre::phoenix::sensors::SensorVelocityMeasPeriod velocityMeasurementPeriod
Desired period for velocity measurement.
Definition: BaseMotorController.h:319
bool reverseSoftLimitEnable
Enable reverse soft limit.
Definition: BaseMotorController.h:339
FilterConfiguration remoteFilter0
Configuration for RemoteFilter 0.
Definition: BaseMotorController.h:371
BaseMotorControllerConfiguration()
Definition: BaseMotorController.h:436
bool clearPositionOnLimitF
Clear the position on forward limit.
Definition: BaseMotorController.h:406
bool limitSwitchDisableNeutralOnLOS
Disable neutral'ing the motor when remote limit switch is lost on CAN bus.
Definition: BaseMotorController.h:418
double nominalOutputForward
Nominal/Minimum output in forward direction [0,1].
Definition: BaseMotorController.h:296
std::string toString()
Definition: BaseMotorController.h:474
double peakOutputReverse
Peak output in reverse direction [-1,0].
Definition: BaseMotorController.h:292
SlotConfiguration slot1
Configuration for slot 1.
Definition: BaseMotorController.h:347
double forwardSoftLimitThreshold
Threshold for soft limits in forward direction (in raw sensor units)
Definition: BaseMotorController.h:327
Base set of configurables related to PID.
Definition: BaseMotorController.h:50
BasePIDSetConfiguration()
Definition: BaseMotorController.h:57
double selectedFeedbackCoefficient
Feedback coefficient of selected sensor.
Definition: BaseMotorController.h:55
std::string toString()
Definition: BaseMotorController.h:65
std::string toString(const std::string &prependString)
Definition: BaseMotorController.h:74
Util class to help with filter configs.
Definition: BaseMotorController.h:123
static bool RemoteSensorSourceDifferent(const FilterConfiguration &settings)
Definition: BaseMotorController.h:134
static bool RemoteSensorDeviceIDDifferent(const FilterConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseMotorController.h:133
static bool FilterConfigurationDifferent(const FilterConfiguration &settings)
Definition: BaseMotorController.h:135
Configurations for filters.
Definition: BaseMotorController.h:83
std::string toString(std::string prependString)
Definition: BaseMotorController.h:111
std::string toString()
Definition: BaseMotorController.h:103
FilterConfiguration()
Definition: BaseMotorController.h:94
int remoteSensorDeviceID
Remote Sensor's device ID.
Definition: BaseMotorController.h:88
RemoteSensorSource remoteSensorSource
The remote sensor device and signal type to bind.
Definition: BaseMotorController.h:92
Configurables available to a slot.
Definition: BaseMotorController.h:142
double maxIntegralAccumulator
Max integral accumulator (in native units)
Definition: BaseMotorController.h:194
std::string toString(std::string prependString)
Definition: BaseMotorController.h:229
double allowableClosedloopError
Allowable closed loop error to neutral (in native units)
Definition: BaseMotorController.h:190
double kD
D Gain.
Definition: BaseMotorController.h:168
int closedLoopPeriod
Desired period of closed loop [1,64]ms.
Definition: BaseMotorController.h:202
SlotConfiguration()
Definition: BaseMotorController.h:204
std::string toString()
Definition: BaseMotorController.h:220
double kI
I Gain.
Definition: BaseMotorController.h:160
double kP
P Gain.
Definition: BaseMotorController.h:151
double kF
F Gain.
Definition: BaseMotorController.h:177
double closedLoopPeakOutput
Peak output from closed loop [0,1].
Definition: BaseMotorController.h:198
double integralZone
Integral zone (in native units)
Definition: BaseMotorController.h:185