| #include "ctre/phoenix/MotorControl/CAN/TalonSRX.h" |
| #include "ctre/phoenix/CCI/MotController_CCI.h" |
| #include "HAL/HAL.h" |
| |
| using namespace ctre::phoenix; |
| using namespace ctre::phoenix::motorcontrol::can; |
| using namespace ctre::phoenix::motorcontrol; |
| |
| /** |
| * Constructor |
| * @param deviceNumber [0,62] |
| */ |
| TalonSRX::TalonSRX(int deviceNumber) : |
| BaseMotorController(deviceNumber | 0x02040000) { |
| HAL_Report(HALUsageReporting::kResourceType_CANTalonSRX, deviceNumber + 1); |
| } |
| /** |
| * Select the feedback device for the motor controller. |
| * |
| * @param feedbackDevice |
| * Feedback Device to select. |
| * @param pidIdx |
| * 0 for Primary closed-loop. 1 for auxiliary closed-loop. |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, |
| int pidIdx, int timeoutMs) { |
| return BaseMotorController::ConfigSelectedFeedbackSensor(feedbackDevice, |
| pidIdx, timeoutMs); |
| } |
| /** |
| * Select the remote feedback device for the motor controller. |
| * Most CTRE CAN motor controllers will support remote sensors over CAN. |
| * |
| * @param feedbackDevice |
| * Remote Feedback Device to select. |
| * @param pidIdx |
| * 0 for Primary closed-loop. 1 for auxiliary closed-loop. |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, |
| int pidIdx, int timeoutMs) { |
| return BaseMotorController::ConfigSelectedFeedbackSensor(feedbackDevice, |
| pidIdx, timeoutMs); |
| } |
| /** |
| * Sets the period of the given status frame. |
| * |
| * User ensure CAN Bus utilization is not high. |
| * |
| * This setting is not persistent and is lost when device is reset. |
| * If this is a concern, calling application can use HasReset() |
| * to determine if the status frame needs to be reconfigured. |
| * |
| * @param frame |
| * Frame whose period is to be changed. |
| * @param periodMs |
| * Period in ms for the given frame. |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::SetStatusFramePeriod(StatusFrameEnhanced frame, |
| int periodMs, int timeoutMs) { |
| return BaseMotorController::SetStatusFramePeriod(frame, periodMs, timeoutMs); |
| } |
| /** |
| * Sets the period of the given status frame. |
| * |
| * User ensure CAN Bus utilization is not high. |
| * |
| * This setting is not persistent and is lost when device is reset. |
| * If this is a concern, calling application can use HasReset() |
| * to determine if the status frame needs to be reconfigured. |
| * |
| * @param frame |
| * Frame whose period is to be changed. |
| * @param periodMs |
| * Period in ms for the given frame. |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::SetStatusFramePeriod(StatusFrame frame, |
| int periodMs, int timeoutMs) { |
| return BaseMotorController::SetStatusFramePeriod(frame, periodMs, timeoutMs); |
| } |
| /** |
| * Gets the period of the given status frame. |
| * |
| * @param frame |
| * Frame to get the period of. |
| * @param 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. |
| * @return Period of the given status frame. |
| */ |
| int TalonSRX::GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs) { |
| return BaseMotorController::GetStatusFramePeriod(frame, timeoutMs); |
| } |
| /** |
| * Gets the period of the given status frame. |
| * |
| * @param frame |
| * Frame to get the period of. |
| * @param 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. |
| * @return Period of the given status frame. |
| */ |
| int TalonSRX::GetStatusFramePeriod(StatusFrame frame, int timeoutMs) { |
| return BaseMotorController::GetStatusFramePeriod(frame, timeoutMs); |
| } |
| /** |
| * Configures the period of each velocity sample. |
| * Every 1ms a position value is sampled, and the delta between that sample |
| * and the position sampled kPeriod ms ago is inserted into a filter. |
| * kPeriod is configured with this function. |
| * |
| * @param period |
| * Desired period for the velocity measurement. @see |
| * #VelocityMeasPeriod |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigVelocityMeasurementPeriod(VelocityMeasPeriod period, |
| int timeoutMs) { |
| return BaseMotorController::ConfigVelocityMeasurementPeriod(period, |
| timeoutMs); |
| } |
| /** |
| * Sets the number of velocity samples used in the rolling average velocity |
| * measurement. |
| * |
| * @param windowSize |
| * Number of samples in the rolling average of velocity |
| * measurement. Valid values are 1,2,4,8,16,32. If another |
| * value is specified, it will truncate to nearest support value. |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigVelocityMeasurementWindow(int windowSize, |
| int timeoutMs) { |
| return BaseMotorController::ConfigVelocityMeasurementWindow(windowSize, |
| timeoutMs); |
| } |
| /** |
| * Configures a limit switch for a local/remote source. |
| * |
| * For example, a CAN motor controller may need to monitor the Limit-R pin |
| * of another Talon, CANifier, or local Gadgeteer feedback connector. |
| * |
| * If the sensor is remote, a device ID of zero is assumed. |
| * If that's not desired, use the four parameter version of this function. |
| * |
| * @param limitSwitchSource |
| * Limit switch source. |
| * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature. |
| * @param normalOpenOrClose |
| * Setting for normally open, normally closed, or disabled. This setting |
| * matches the web-based configuration drop down. |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigForwardLimitSwitchSource( |
| LimitSwitchSource limitSwitchSource, |
| LimitSwitchNormal normalOpenOrClose, int timeoutMs) { |
| |
| return BaseMotorController::ConfigForwardLimitSwitchSource( |
| limitSwitchSource, normalOpenOrClose, timeoutMs); |
| } |
| /** |
| * Configures a limit switch for a local/remote source. |
| * |
| * For example, a CAN motor controller may need to monitor the Limit-R pin |
| * of another Talon, CANifier, or local Gadgeteer feedback connector. |
| * |
| * If the sensor is remote, a device ID of zero is assumed. |
| * If that's not desired, use the four parameter version of this function. |
| * |
| * @param limitSwitchSource |
| * Limit switch source. @see #LimitSwitchSource |
| * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature. |
| * @param normalOpenOrClose |
| * Setting for normally open, normally closed, or disabled. This setting |
| * matches the web-based configuration drop down. |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigReverseLimitSwitchSource( |
| LimitSwitchSource limitSwitchSource, |
| LimitSwitchNormal normalOpenOrClose, int timeoutMs) { |
| return BaseMotorController::ConfigReverseLimitSwitchSource( |
| limitSwitchSource, normalOpenOrClose, timeoutMs); |
| } |
| /** |
| * Configures the forward limit switch for a remote source. |
| * For example, a CAN motor controller may need to monitor the Limit-F pin |
| * of another Talon or CANifier. |
| * |
| * @param limitSwitchSource |
| * Remote limit switch source. |
| * User can choose between a remote Talon SRX, CANifier, or deactivate the feature. |
| * @param normalOpenOrClose |
| * Setting for normally open, normally closed, or disabled. This setting |
| * matches the web-based configuration drop down. |
| * @param deviceID |
| * Device ID of remote source (Talon SRX or CANifier device ID). |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigForwardLimitSwitchSource( |
| RemoteLimitSwitchSource limitSwitchSource, |
| LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs) { |
| |
| return BaseMotorController::ConfigForwardLimitSwitchSource( |
| limitSwitchSource, normalOpenOrClose, deviceID, timeoutMs); |
| } |
| /** |
| * Configures the reverse limit switch for a remote source. |
| * For example, a CAN motor controller may need to monitor the Limit-R pin |
| * of another Talon or CANifier. |
| * |
| * @param limitSwitchSource |
| * Remote limit switch source. |
| * User can choose between a remote Talon SRX, CANifier, or deactivate the feature. |
| * @param normalOpenOrClose |
| * Setting for normally open, normally closed, or disabled. This setting |
| * matches the web-based configuration drop down. |
| * @param deviceID |
| * Device ID of remote source (Talon SRX or CANifier device ID). |
| * @param 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. |
| * @return Error Code generated by function. 0 indicates no error. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigReverseLimitSwitchSource( |
| RemoteLimitSwitchSource limitSwitchSource, |
| LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs) { |
| |
| return BaseMotorController::ConfigReverseLimitSwitchSource( |
| limitSwitchSource, normalOpenOrClose, deviceID, timeoutMs); |
| } |
| |
| //------ Current Lim ----------// |
| /** |
| * Configure the peak allowable current (when current limit is enabled). |
| * |
| * Current limit is activated when current exceeds the peak limit for longer than the peak duration. |
| * Then software will limit to the continuous limit. |
| * This ensures current limiting while allowing for momentary excess current events. |
| * |
| * For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() |
| * and set the peak to zero: ConfigPeakCurrentLimit(0). |
| * |
| * @param amps Amperes to limit. |
| * @param 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. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigPeakCurrentLimit(int amps, int timeoutMs) { |
| return c_MotController_ConfigPeakCurrentLimit(m_handle, amps, timeoutMs); |
| } |
| /** |
| * Configure the peak allowable duration (when current limit is enabled). |
| * |
| * Current limit is activated when current exceeds the peak limit for longer than the peak duration. |
| * Then software will limit to the continuous limit. |
| * This ensures current limiting while allowing for momentary excess current events. |
| * |
| * For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() |
| * and set the peak to zero: ConfigPeakCurrentLimit(0). |
| * |
| * @param milliseconds How long to allow current-draw past peak limit. |
| * @param 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. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigPeakCurrentDuration(int milliseconds, int timeoutMs) { |
| return c_MotController_ConfigPeakCurrentDuration(m_handle, milliseconds, |
| timeoutMs); |
| } |
| /** |
| * Configure the continuous allowable current-draw (when current limit is enabled). |
| * |
| * Current limit is activated when current exceeds the peak limit for longer than the peak duration. |
| * Then software will limit to the continuous limit. |
| * This ensures current limiting while allowing for momentary excess current events. |
| * |
| * For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() |
| * and set the peak to zero: ConfigPeakCurrentLimit(0). |
| * |
| * @param amps Amperes to limit. |
| * @param 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. |
| */ |
| ctre::phoenix::ErrorCode TalonSRX::ConfigContinuousCurrentLimit(int amps, int timeoutMs) { |
| return c_MotController_ConfigContinuousCurrentLimit(m_handle, amps, timeoutMs); |
| } |
| /** |
| * Enable or disable Current Limit. |
| * @param enable |
| * Enable state of current limit. |
| * @see ConfigPeakCurrentLimit, ConfigPeakCurrentDuration, ConfigContinuousCurrentLimit |
| */ |
| void TalonSRX::EnableCurrentLimit(bool enable) { |
| c_MotController_EnableCurrentLimit(m_handle, enable); |
| } |
| |