CTRE Phoenix C++ 5.33.1
TalonSRX.h
Go to the documentation of this file.
1/* Copyright (C) Cross The Road Electronics 2024 */
2#pragma once
3#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
4#pragma warning (push)
5#pragma warning (disable : 4250)
6#endif
7
11
12/* forward proto's */
13namespace ctre {
14 namespace phoenix {
15 namespace motorcontrol {
16 class SensorCollection;
17 class TalonSRXSimCollection;
18 }
19 }
20}
21
22namespace ctre {
23 namespace phoenix {
24 namespace motorcontrol {
25 namespace can {
26
27 /**
28 * Configurables available to TalonSRX's PID
29 */
31 /**
32 * Configurables available to TalonSRX
33 */
35
36 /**
37 * Peak current in amps
38 *
39 * Current limit is activated when current exceeds the peak limit for longer
40 * than the peak duration. Then software will limit to the continuous limit.
41 * This ensures current limiting while allowing for momentary excess current
42 * events.
43 */
45 /**
46 * Peak Current duration in milliseconds
47 *
48 * Current limit is activated when current exceeds the peak limit for longer
49 * than the peak duration. Then software will limit to the continuous limit.
50 * This ensures current limiting while allowing for momentary excess current
51 * events.
52 */
54 /**
55 * Continuous current in amps
56 *
57 * Current limit is activated when current exceeds the peak limit for longer
58 * than the peak duration. Then software will limit to the continuous limit.
59 * This ensures current limiting while allowing for momentary excess current
60 * events.
61 */
68 {
69 }
70
71 /**
72 * @return String representation of all the configs
73 */
74 std::string toString() {
75 return toString("");
76 }
77
78 /**
79 * @param prependString
80 * String to prepend to all the configs
81 * @return String representation of all the configs
82 */
83 std::string toString(std::string prependString) {
84
85 std::string retstr;
86 retstr += prependString + ".peakCurrentLimit = " + std::to_string(peakCurrentLimit) + ";\n";
87 retstr += prependString + ".peakCurrentDuration = " + std::to_string(peakCurrentDuration) + ";\n";
88 retstr += prependString + ".continuousCurrentLimit = " + std::to_string(continuousCurrentLimit) + ";\n";
89 retstr += BaseTalonConfiguration::toString(prependString);
90
91 return retstr;
92 }
93 };// struct TalonSRXConfiguration
94
95 /**
96 * Util class to help with talon configs
97 */
99 private:
100 static struct TalonSRXConfiguration _default;
101 public:
102 /**
103 * Determine if specified value is different from default
104 * @param settings settings to compare against
105 * @return if specified value is different from default
106 * @{
107 */
108 static bool PeakCurrentLimitDifferent(const TalonSRXConfiguration& settings) { return (!(settings.peakCurrentLimit == _default.peakCurrentLimit)) || !settings.enableOptimizations; }
109 static bool PeakCurrentDurationDifferent(const TalonSRXConfiguration& settings) { return (!(settings.peakCurrentDuration == _default.peakCurrentDuration)) || !settings.enableOptimizations; }
110 static bool ContinuousCurrentLimitDifferent(const TalonSRXConfiguration& settings) { return (!(settings.continuousCurrentLimit == _default.continuousCurrentLimit)) || !settings.enableOptimizations; }
111
112 /** @} */
113 };
114
115 /**
116 * CTRE Talon SRX Motor Controller when used on CAN Bus.
117 *
118 * <pre>
119 * {@code
120 * // Example usage of a TalonSRX motor controller
121 * TalonSRX motor{0}; // creates a new TalonSRX with ID 0
122 *
123 * TalonSRXConfiguration config;
124 * config.peakCurrentLimit = 40; // the peak current, in amps
125 * config.peakCurrentDuration = 1500; // the time at the peak current before the limit triggers, in ms
126 * config.continuousCurrentLimit = 30; // the current to maintain if the peak limit is triggered
127 * motor.ConfigAllSettings(config); // apply the config settings; this selects the quadrature encoder
128 *
129 * motor.Set(TalonSRXControlMode::PercentOutput, 0.5); // runs the motor at 50% power
130 *
131 * std::cout << motor.GetSelectedSensorPosition() << std::endl; // prints the position of the selected sensor
132 * std::cout << motor.GetSelectedSensorVelocity() << std::endl; // prints the velocity recorded by the selected sensor
133 * std::cout << motor.GetMotorOutputPercent() << std::endl; // prints the percent output of the motor (0.5)
134 * std::cout << motor.GetStatorCurrent() << std::endl; // prints the output current of the motor
135 *
136 * ErrorCode error = motor.GetLastError(); // gets the last error generated by the motor controller
137 * Faults faults;
138 * ErrorCode faultsError = motor.GetFaults(faults); // fills faults with the current motor controller faults; returns the last error generated
139 *
140 * motor.SetStatusFramePeriod(StatusFrameEnhanced::Status_2_Feedback0, 10); // changes the period of the Status 2 frame (GetSelectedSensor*()) to 10ms
141 * }
142 * </pre>
143 */
144 class TalonSRX : public virtual BaseTalon
145 {
146 private:
147
148 public:
149 /**
150 * Constructor for a Talon
151 * @param deviceNumber CAN Device ID of TalonSRX
152 */
153 TalonSRX(int deviceNumber);
154
155#ifndef __FRC_ROBORIO__
156 /**
157 * Constructor so non-FRC platforms can specify a CAN 2.0 socketcan bus
158 * @param deviceNumber CAN Device ID of TalonSRX
159 * @param canbus String specifying the bus
160 */
161 TalonSRX(int deviceNumber, std::string const &canbus);
162#endif
163
165 TalonSRX() = delete;
166 TalonSRX(TalonSRX const&) = delete;
167 TalonSRX& operator=(TalonSRX const&) = delete;
168 // ------ Set output routines. ----------//
169 /**
170 * Sets the appropriate output on the talon, depending on the mode.
171 * @param mode The output mode to apply.
172 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
173 * In Current mode, output value is in amperes.
174 * In Velocity mode, output value is in position change / 100ms.
175 * In Position mode, output value is in encoder ticks or an analog value,
176 * depending on the sensor.
177 * In Follower mode, the output value is the integer device ID of the talon to
178 * duplicate.
179 *
180 * @param value The setpoint value, as described above.
181 *
182 *
183 * Standard Driving Example:
184 * _talonLeft.set(ControlMode.PercentOutput, leftJoy);
185 * _talonRght.set(ControlMode.PercentOutput, rghtJoy);
186 */
187 void Set(TalonSRXControlMode mode, double value);
188 /**
189 * @param mode Sets the appropriate output on the talon, depending on the mode.
190 * @param demand0 The output value to apply.
191 * such as advanced feed forward and/or auxiliary close-looping in firmware.
192 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
193 * In Current mode, output value is in amperes.
194 * In Velocity mode, output value is in position change / 100ms.
195 * In Position mode, output value is in encoder ticks or an analog value,
196 * depending on the sensor. See
197 * In Follower mode, the output value is the integer device ID of the talon to
198 * duplicate.
199 *
200 * @param demand1Type The demand type for demand1.
201 * Neutral: Ignore demand1 and apply no change to the demand0 output.
202 * AuxPID: Use demand1 to set the target for the auxiliary PID 1. Auxiliary
203 * PID is always executed as standard Position PID control.
204 * ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the
205 * demand0 output. In PercentOutput the demand0 output is the motor output,
206 * and in closed-loop modes the demand0 output is the output of PID0.
207 * @param demand1 Supplmental output value.
208 * AuxPID: Target position in Sensor Units
209 * ArbitraryFeedForward: Percent Output between -1.0 and 1.0
210 *
211 *
212 * Arcade Drive Example:
213 * _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn);
214 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);
215 *
216 * Drive Straight Example:
217 * Note: Selected Sensor Configuration is necessary for both PID0 and PID1.
218 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
219 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);
220 *
221 * Drive Straight to a Distance Example:
222 * Note: Other configurations (sensor selection, PID gains, etc.) need to be set.
223 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
224 * _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
225 */
226 void Set(TalonSRXControlMode mode, double demand0, DemandType demand1Type, double demand1);
227 //------ sensor selection ----------//
228 /**
229 * Select the feedback device for the motor controller.
230 *
231 * @param feedbackDevice
232 * Talon SRX Feedback Device to select.
233 * @param pidIdx
234 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
235 * @param timeoutMs
236 * Timeout value in ms. If nonzero, function will wait for
237 * config success and report an error if it times out.
238 * If zero, no blocking or checking is performed.
239 * @return Error Code generated by function. 0 indicates no error.
240 */
241 ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(TalonSRXFeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
242 /**
243 * Select the feedback device for the motor controller.
244 *
245 * @param feedbackDevice
246 * Feedback Device to select.
247 * @param pidIdx
248 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
249 * @param timeoutMs
250 * Timeout value in ms. If nonzero, function will wait for
251 * config success and report an error if it times out.
252 * If zero, no blocking or checking is performed.
253 * @return Error Code generated by function. 0 indicates no error.
254 */
255 ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx, int timeoutMs = 0);
256
257 /**
258 * Select the remote feedback device for the motor controller.
259 * Most CTRE CAN motor controllers will support remote sensors over CAN.
260 *
261 * @param feedbackDevice
262 * Remote Feedback Device to select.
263 * @param pidIdx
264 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
265 * @param timeoutMs
266 * Timeout value in ms. If nonzero, function will wait for
267 * config success and report an error if it times out.
268 * If zero, no blocking or checking is performed.
269 * @return Error Code generated by function. 0 indicates no error.
270 */
272
273 //------ Current Limit ----------//
274 /**
275 * Configures the supply (input) current limit.
276 * @param currLimitConfigs Current limit configuration
277 * @param timeoutMs
278 * Timeout value in ms. If nonzero, function will wait for
279 * config success and report an error if it times out.
280 * If zero, no blocking or checking is performed.
281 * @return Error Code generated by function. 0 indicates no error.
282 */
283 virtual ctre::phoenix::ErrorCode ConfigSupplyCurrentLimit(const SupplyCurrentLimitConfiguration& currLimitConfigs, int timeoutMs = 50);
284 /**
285 * Configure the peak allowable current (when current limit is enabled).
286 *
287 * Supply current limiting is also available via ConfigSupplyCurrentLimit(),
288 * which is a common routine with Talon FX.
289 *
290 * Current limit is activated when current exceeds the peak limit for longer
291 * than the peak duration. Then software will limit to the continuous limit.
292 * This ensures current limiting while allowing for momentary excess current
293 * events.
294 *
295 * For simpler current-limiting (single threshold) use
296 * ConfigContinuousCurrentLimit() and set the peak to zero:
297 * ConfigPeakCurrentLimit(0).
298 *
299 * @param amps
300 * Amperes to limit.
301 * @param timeoutMs
302 * Timeout value in ms. If nonzero, function will wait for config
303 * success and report an error if it times out. If zero, no
304 * blocking or checking is performed.
305 */
307 /**
308 * Configure the peak allowable duration (when current limit is enabled).
309 *
310 * Supply current limiting is also available via ConfigSupplyCurrentLimit(),
311 * which is a common routine with Talon FX.
312 *
313 * Current limit is activated when current exceeds the peak limit for longer
314 * than the peak duration. Then software will limit to the continuous limit.
315 * This ensures current limiting while allowing for momentary excess current
316 * events.
317 *
318 * For simpler current-limiting (single threshold) use
319 * ConfigContinuousCurrentLimit() and set the peak to zero:
320 * ConfigPeakCurrentLimit(0).
321 *
322 * @param milliseconds
323 * How long to allow current-draw past peak limit.
324 * @param timeoutMs
325 * Timeout value in ms. If nonzero, function will wait for config
326 * success and report an error if it times out. If zero, no
327 * blocking or checking is performed.
328 */
330 int timeoutMs = 0);
331 /**
332 * Configure the continuous allowable current-draw (when current limit is
333 * enabled).
334 *
335 * Supply current limiting is also available via ConfigSupplyCurrentLimit(),
336 * which is a common routine with Talon FX.
337 *
338 * Current limit is activated when current exceeds the peak limit for longer
339 * than the peak duration. Then software will limit to the continuous limit.
340 * This ensures current limiting while allowing for momentary excess current
341 * events.
342 *
343 * For simpler current-limiting (single threshold) use
344 * ConfigContinuousCurrentLimit() and set the peak to zero:
345 * ConfigPeakCurrentLimit(0).
346 *
347 * @param amps
348 * Amperes to limit.
349 * @param timeoutMs
350 * Timeout value in ms. If nonzero, function will wait for config
351 * success and report an error if it times out. If zero, no
352 * blocking or checking is performed.
353 */
355
356 /**
357 * Enable or disable Current Limit.
358 *
359 * Supply current limiting is also available via ConfigSupplyCurrentLimit(),
360 * which is a common routine with Talon FX.
361 *
362 * @param enable
363 * Enable state of current limit.
364 * @see configPeakCurrentLimit()
365 * @see configPeakCurrentDuration()
366 * @see configContinuousCurrentLimit()
367 */
368 void EnableCurrentLimit(bool enable);
369 //------ RAW Sensor API ----------//
370 /**
371 * @return object that can get/set individual RAW sensor values.
372 */
374
375 //------ Simulation API ----------//
376 /**
377 * @return object that can set simulation inputs.
378 */
380
381 //------ All Configs ----------//
382
383 /**
384 * Sets all PID persistant settings.
385 *
386 * @param pid Object with all of the PID set persistant settings
387 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop.
388 * @param timeoutMs
389 * Timeout value in ms. If nonzero, function will wait for
390 * config success and report an error if it times out.
391 * If zero, no blocking or checking is performed.
392 */
393 ctre::phoenix::ErrorCode ConfigurePID(const TalonSRXPIDSetConfiguration& pid, int pidIdx = 0, int timeoutMs = 50);
394 /**
395 * Gets all PID set persistant settings.
396 *
397 * @param pid Object with all of the PID set persistant settings
398 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop.
399 * @param timeoutMs
400 * Timeout value in ms. If nonzero, function will wait for
401 * config success and report an error if it times out.
402 * If zero, no blocking or checking is performed.
403 */
404 void GetPIDConfigs(TalonSRXPIDSetConfiguration& pid, int pidIdx = 0, int timeoutMs = 50);
405 /**
406 * Configures all persistent settings.
407 *
408 * @param allConfigs Object with all of the persistant settings
409 * @param timeoutMs
410 * Timeout value in ms. If nonzero, function will wait for
411 * config success and report an error if it times out.
412 * If zero, no blocking or checking is performed.
413 *
414 * @return Error Code generated by function. 0 indicates no error.
415 */
417 /**
418 * Gets all persistant settings.
419 *
420 * @param allConfigs Object with all of the persistant settings
421 * @param timeoutMs
422 * Timeout value in ms. If nonzero, function will wait for
423 * config success and report an error if it times out.
424 * If zero, no blocking or checking is performed.
425 */
426 void GetAllConfigs(TalonSRXConfiguration& allConfigs, int timeoutMs = 50);
427
428 /* ----- virtual re-directs ------- */
429 virtual void Set(ControlMode mode, double value);
430 virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1);
431 };// class TalonSRX
432
433 } // namespace can
434 } // namespace motorcontrol
435 } // namespace phoenix
436} // namespace ctre
437
438#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
439#pragma warning (pop)
440#endif
Collection of sensors available to a motor controller.
Definition: SensorCollection.h:31
Collection of simulation commands available to a TalonSRX motor controller.
Definition: TalonSRXSimCollection.h:26
Util class to help with talon configs.
Definition: BaseTalon.h:230
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: BaseTalon.h:267
Util class to help with talon configs.
Definition: TalonSRX.h:98
static bool ContinuousCurrentLimitDifferent(const TalonSRXConfiguration &settings)
Definition: TalonSRX.h:110
static bool PeakCurrentDurationDifferent(const TalonSRXConfiguration &settings)
Definition: TalonSRX.h:109
static bool PeakCurrentLimitDifferent(const TalonSRXConfiguration &settings)
Determine if specified value is different from default.
Definition: TalonSRX.h:108
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: TalonSRX.h:145
virtual ctre::phoenix::ErrorCode ConfigSupplyCurrentLimit(const SupplyCurrentLimitConfiguration &currLimitConfigs, int timeoutMs=50)
Configures the supply (input) current limit.
TalonSRX(int deviceNumber)
Constructor for a Talon.
ctre::phoenix::ErrorCode ConfigurePID(const TalonSRXPIDSetConfiguration &pid, int pidIdx=0, int timeoutMs=50)
Sets all PID persistant settings.
ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx, int timeoutMs)
Select the remote feedback device for the motor controller.
ctre::phoenix::ErrorCode ConfigContinuousCurrentLimit(int amps, int timeoutMs=0)
Configure the continuous allowable current-draw (when current limit is enabled).
ctre::phoenix::motorcontrol::TalonSRXSimCollection & GetSimCollection()
ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx, int timeoutMs=0)
Select the feedback device for the motor controller.
virtual void Set(ControlMode mode, double value)
Sets the appropriate output on the talon, depending on the mode.
TalonSRX(int deviceNumber, std::string const &canbus)
Constructor so non-FRC platforms can specify a CAN 2.0 socketcan bus.
ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(TalonSRXFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the feedback device for the motor controller.
ctre::phoenix::ErrorCode ConfigPeakCurrentLimit(int amps, int timeoutMs=0)
Configure the peak allowable current (when current limit is enabled).
void EnableCurrentLimit(bool enable)
Enable or disable Current Limit.
void GetAllConfigs(TalonSRXConfiguration &allConfigs, int timeoutMs=50)
Gets all persistant settings.
TalonSRX & operator=(TalonSRX const &)=delete
void Set(TalonSRXControlMode mode, double value)
Sets the appropriate output on the talon, depending on the mode.
ctre::phoenix::motorcontrol::SensorCollection & GetSensorCollection()
void GetPIDConfigs(TalonSRXPIDSetConfiguration &pid, int pidIdx=0, int timeoutMs=50)
Gets all PID set persistant settings.
void Set(TalonSRXControlMode mode, double demand0, DemandType demand1Type, double demand1)
virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1)
ctre::phoenix::ErrorCode ConfigAllSettings(const TalonSRXConfiguration &allConfigs, int timeoutMs=50)
Configures all persistent settings.
ctre::phoenix::ErrorCode ConfigPeakCurrentDuration(int milliseconds, int timeoutMs=0)
Configure the peak allowable duration (when current limit is enabled).
ControlMode
Choose the control mode for a motor controller.
Definition: ControlMode.h:11
DemandType
How to interpret a demand value.
Definition: DemandType.h:10
RemoteFeedbackDevice
Choose the remote feedback device for a motor controller.
Definition: FeedbackDevice.h:179
FeedbackDevice
Choose the feedback device for a motor controller.
Definition: FeedbackDevice.h:14
TalonSRXFeedbackDevice
Choose the feedback device for a Talon SRX.
Definition: FeedbackDevice.h:76
TalonSRXControlMode
Choose the control mode for a Talon SRX.
Definition: ControlMode.h:114
ErrorCode
Definition: ErrorCode.h:13
namespace ctre
Definition: paramEnum.h:5
bool enableOptimizations
Enable optimizations for ConfigAll (defaults true)
Definition: CustomParamConfiguration.h:23
Describes the desired stator current limiting behavior.
Definition: SupplyCurrentLimitConfiguration.h:13
Configurables available to BaseTalon.
Definition: BaseTalon.h:96
std::string toString()
Definition: BaseTalon.h:197
Configurables available to BaseTalon's PID.
Definition: BaseTalon.h:34
Configurables available to TalonSRX.
Definition: TalonSRX.h:34
std::string toString()
Definition: TalonSRX.h:74
int continuousCurrentLimit
Continuous current in amps.
Definition: TalonSRX.h:62
std::string toString(std::string prependString)
Definition: TalonSRX.h:83
int peakCurrentLimit
Peak current in amps.
Definition: TalonSRX.h:44
int peakCurrentDuration
Peak Current duration in milliseconds.
Definition: TalonSRX.h:53
Configurables available to TalonSRX's PID.
Definition: TalonSRX.h:30