2025-Robot
Robot code for 2025 FRC season by Argos, FRC team #1756
Loading...
Searching...
No Matches
falcon_config.h
Go to the documentation of this file.
1
4
5#pragma once
6
7#include <units/current.h>
8#include <units/time.h>
9
10#include <iostream>
11
12#include <ctre/phoenix6/TalonFX.hpp>
13
16#include "status_frame_config.h"
17
18namespace argos_lib {
19 namespace falcon_config {
20
21 HAS_MEMBER(forwardLimit_deviceID)
22 HAS_MEMBER(forwardLimit_normalState)
23 HAS_MEMBER(forwardLimit_source)
24 HAS_MEMBER(inverted)
25 HAS_MEMBER(neutralDeadband)
26 HAS_MEMBER(neutralMode)
27 HAS_MEMBER(dutyCycleNeutralDeadband)
28 HAS_MEMBER(nominalOutputForward)
29 HAS_MEMBER(nominalOutputReverse)
30 HAS_MEMBER(peakOutputForward)
31 HAS_MEMBER(peakOutputReverse)
32 HAS_MEMBER(voltageOpenLoopRampPeriod)
33 HAS_MEMBER(dutyCycleOpenLoopRampPeriod)
34 HAS_MEMBER(pid0_kP)
35 HAS_MEMBER(pid0_kI)
36 HAS_MEMBER(pid0_kD)
37 HAS_MEMBER(pid0_kS)
38 HAS_MEMBER(pid0_kV)
39 HAS_MEMBER(pid0_kA)
40 HAS_MEMBER(pid0_kG)
41 HAS_MEMBER(pid0_gravityType)
42 HAS_MEMBER(pid1_kP)
43 HAS_MEMBER(pid1_kI)
44 HAS_MEMBER(pid1_kD)
45 HAS_MEMBER(pid1_kS)
46 HAS_MEMBER(pid1_kV)
47 HAS_MEMBER(pid1_kA)
48 HAS_MEMBER(pid1_gravityType)
49 HAS_MEMBER(pid1_kG)
50 HAS_MEMBER(motionMagic_cruiseVelocity)
51 HAS_MEMBER(motionMagic_acceleration)
52 HAS_MEMBER(motionMagic_jerk)
53 HAS_MEMBER(motionMagic_expo_kV)
54 HAS_MEMBER(motionMagic_expo_kA)
55 HAS_MEMBER(reverseLimit_deviceID)
56 HAS_MEMBER(reverseLimit_normalState)
57 HAS_MEMBER(reverseLimit_source)
58 HAS_MEMBER(rotorToSensorRatio)
59 HAS_MEMBER(selectedSensor)
60 HAS_MEMBER(selectedSensor_addr)
61 HAS_MEMBER(sensorToMechanismRatio)
62 HAS_MEMBER(statorCurrentLimit)
63 HAS_MEMBER(statusFrameMotorMode)
64 HAS_MEMBER(supplyCurrentLimit)
65 HAS_MEMBER(supplyCurrentLowerLimit)
66 HAS_MEMBER(supplyCurrentLowerTime)
67
122 template <typename T>
123 bool FalconConfig(ctre::phoenix6::hardware::TalonFX& motorController, units::millisecond_t configTimeout) {
124 ctre::phoenix6::configs::TalonFXConfiguration config;
125
126 if constexpr (has_inverted<T>{}) {
127 config.MotorOutput.Inverted = T::inverted;
128 }
129 if constexpr (has_neutralMode<T>{}) {
130 config.MotorOutput.NeutralMode = T::neutralMode;
131 }
132 if constexpr (has_dutyCycleNeutralDeadband<T>{}) {
133 config.MotorOutput.DutyCycleNeutralDeadband = T::dutyCycleNeutralDeadband;
134 }
135 if constexpr (has_selectedSensor_addr<T>{}) {
136 static_assert(has_selectedSensor<T>{} &&
137 T::selectedSensor != ctre::phoenix6::signals::FeedbackSensorSourceValue::RotorSensor,
138 "Remote sensor required when address provided");
139 static_assert(T::selectedSensor_addr.address >= 0, "Remote sensor address must be non-negative");
140 config.Feedback.FeedbackRemoteSensorID = T::selectedSensor_addr.address;
141 }
142 if constexpr (has_peakOutputForward<T>{}) {
143 config.MotorOutput.PeakForwardDutyCycle = T::peakOutputForward;
144 }
145 if constexpr (has_peakOutputReverse<T>{}) {
146 config.MotorOutput.PeakReverseDutyCycle = T::peakOutputReverse;
147 }
148 if constexpr (has_voltageOpenLoopRampPeriod<T>{}) {
149 config.OpenLoopRamps.VoltageOpenLoopRampPeriod =
150 std::clamp<units::second_t>(T::voltageOpenLoopRampPeriod, 0_s, 1_s);
151 }
152 if constexpr (has_dutyCycleOpenLoopRampPeriod<T>{}) {
153 config.OpenLoopRamps.DutyCycleOpenLoopRampPeriod =
154 std::clamp<units::second_t>(T::dutyCycleOpenLoopRampPeriod, 0_s, 1_s);
155 }
156 if constexpr (has_selectedSensor<T>{}) {
157 config.Feedback.FeedbackSensorSource = T::selectedSensor;
158 if constexpr (T::selectedSensor == ctre::phoenix6::signals::FeedbackSensorSourceValue::FusedCANcoder) {
159 static_assert(has_sensorToMechanismRatio<T>{}, "Fused CANcoder mode requires sensor to mechanism ratio");
160 static_assert(has_rotorToSensorRatio<T>{}, "Fused CANcoder mode requires rotor to sensor ratio");
161 static_assert(T::sensorToMechanismRatio > 0, "sensorToMechanismRatio must be a positive value");
162 static_assert(T::rotorToSensorRatio > 0, "rotorToSensorRatio must be a positive value");
163 config.Feedback.SensorToMechanismRatio = T::sensorToMechanismRatio;
164 config.Feedback.RotorToSensorRatio = T::rotorToSensorRatio;
165 }
166 }
167 if constexpr (has_pid0_kP<T>{}) {
168 config.Slot0.kP = T::pid0_kP;
169 }
170 if constexpr (has_pid0_kI<T>{}) {
171 config.Slot0.kI = T::pid0_kI;
172 }
173 if constexpr (has_pid0_kD<T>{}) {
174 config.Slot0.kD = T::pid0_kD;
175 }
176 if constexpr (has_pid0_kS<T>{}) {
177 config.Slot0.kS = T::pid0_kS;
178 }
179 if constexpr (has_pid0_kV<T>{}) {
180 config.Slot0.kV = T::pid0_kV;
181 }
182 if constexpr (has_pid0_kA<T>{}) {
183 config.Slot0.kA = T::pid0_kA;
184 }
185 if constexpr (has_pid0_kG<T>{} && has_pid0_gravityType<T>{}) {
186 config.Slot0.kG = T::pid0_kG;
187 config.Slot0.GravityType = T::pid0_gravityType;
188 }
189 if constexpr (has_pid1_kP<T>{}) {
190 config.Slot1.kP = T::pid1_kP;
191 }
192 if constexpr (has_pid1_kI<T>{}) {
193 config.Slot1.kI = T::pid1_kI;
194 }
195 if constexpr (has_pid1_kD<T>{}) {
196 config.Slot1.kD = T::pid1_kD;
197 }
198 if constexpr (has_pid1_kS<T>{}) {
199 config.Slot1.kS = T::pid1_kS;
200 }
201 if constexpr (has_pid1_kV<T>{}) {
202 config.Slot1.kV = T::pid1_kV;
203 }
204 if constexpr (has_pid1_kA<T>{}) {
205 config.Slot1.kA = T::pid1_kA;
206 }
207 if constexpr (has_pid1_kG<T>{} && has_pid1_gravityType<T>{}) {
208 config.Slot1.kG = T::pid1_kG;
209 config.Slot1.GravityType = T::pid1_gravityType;
210 }
211 if constexpr (has_motionMagic_cruiseVelocity<T>{}) {
212 config.MotionMagic.MotionMagicCruiseVelocity = T::motionMagic_cruiseVelocity;
213 }
214 if constexpr (has_motionMagic_acceleration<T>{}) {
215 config.MotionMagic.MotionMagicAcceleration = T::motionMagic_acceleration;
216 }
217 if constexpr (has_motionMagic_jerk<T>{}) {
218 config.MotionMagic.MotionMagicJerk = T::motionMagic_jerk;
219 }
220 if constexpr (has_motionMagic_expo_kV<T>{}) {
221 config.MotionMagic.MotionMagicExpo_kV = T::motionMagic_expo_kV;
222 }
223 if constexpr (has_motionMagic_expo_kA<T>{}) {
224 config.MotionMagic.MotionMagicExpo_kA = T::motionMagic_expo_kA;
225 }
228 config.CurrentLimits.SupplyCurrentLimitEnable = true;
229 if constexpr (has_supplyCurrentLimit<T>{}) {
230 constexpr units::ampere_t currentLimit = T::supplyCurrentLimit;
231 static_assert(currentLimit.to<double>() > 0, "Supply current limit must be positive");
232 config.CurrentLimits.SupplyCurrentLimit = currentLimit.to<double>();
233 }
234 if constexpr (has_supplyCurrentLowerLimit<T>{}) {
235 constexpr units::ampere_t currentThreshold = T::supplyCurrentLowerLimit;
236 static_assert(currentThreshold.to<double>() > 0, "Supply current threshold must be positive");
237 config.CurrentLimits.SupplyCurrentLowerLimit = currentThreshold.to<double>();
238 }
239 if constexpr (has_supplyCurrentLowerTime<T>{}) {
240 constexpr units::second_t currentThresholdTime = T::supplyCurrentLowerTime;
241 static_assert(currentThresholdTime.to<double>() >= 0, "Supply current threshold time must be non-negative");
242 static_assert(currentThresholdTime.to<double>() <= 1.275, "Current duration must be less than 1.275");
243 config.CurrentLimits.SupplyCurrentLowerTime = currentThresholdTime.to<double>();
244 }
245 }
246 if constexpr (has_statorCurrentLimit<T>{}) {
247 config.CurrentLimits.StatorCurrentLimitEnable = true;
248 constexpr units::ampere_t currentLimit = T::statorCurrentLimit;
249 static_assert(currentLimit.to<double>() > 0, "Stator current limit must be positive");
250 config.CurrentLimits.StatorCurrentLimit = currentLimit;
251 }
254 if constexpr (has_forwardLimit_source<T>{}) {
255 constexpr ctre::phoenix6::signals::ForwardLimitSourceValue source = T::forwardLimit_source;
256 if constexpr (source != ctre::phoenix6::signals::ForwardLimitSourceValue::Disabled &&
257 source != ctre::phoenix6::signals::ForwardLimitSourceValue::LimitSwitchPin) {
258 static_assert(has_forwardLimit_deviceID<T>{}, "Forward limit switch requires remote source device ID");
259 }
260 if constexpr (source != ctre::phoenix6::signals::ForwardLimitSourceValue::Disabled) {
261 static_assert(has_forwardLimit_normalState<T>{},
262 "Forward limit switch configuration requires both source and normal state");
263 config.HardwareLimitSwitch.ForwardLimitEnable = true;
264 }
265 config.HardwareLimitSwitch.ForwardLimitSource = T::forwardLimit_source;
266 }
267 if constexpr (has_forwardLimit_deviceID<T>{}) {
268 static_assert(has_forwardLimit_source<T>{} &&
269 T::forwardLimit_source != ctre::phoenix6::signals::ForwardLimitSourceValue::Disabled &&
270 T::forwardLimit_source != ctre::phoenix6::signals::ForwardLimitSourceValue::LimitSwitchPin,
271 "Forward limit switch device ID has no effect when limit source is not remote");
272 config.HardwareLimitSwitch.ForwardLimitRemoteSensorID = T::forwardLimit_deviceID;
273 }
274 if constexpr (has_forwardLimit_normalState<T>{}) {
275 if constexpr (T::forwardLimit_normalState != ctre::phoenix6::signals::ForwardLimitSourceValue::Disabled) {
276 static_assert(has_forwardLimit_source<T>{}, "Forward limit switch source required");
277 }
278 config.HardwareLimitSwitch.ForwardLimitType = T::forwardLimit_normalState;
279 }
280 } else {
281 config.HardwareLimitSwitch.ForwardLimitEnable = false;
282 }
285 if constexpr (has_reverseLimit_source<T>{}) {
286 constexpr ctre::phoenix6::signals::ReverseLimitSourceValue source = T::reverseLimit_source;
287 if constexpr (source != ctre::phoenix6::signals::ReverseLimitSourceValue::Disabled &&
288 source != ctre::phoenix6::signals::ReverseLimitSourceValue::LimitSwitchPin) {
289 static_assert(has_reverseLimit_deviceID<T>{}, "Reverse limit switch requires remote source device ID");
290 }
291 if constexpr (source != ctre::phoenix6::signals::ReverseLimitSourceValue::Disabled) {
292 static_assert(has_reverseLimit_normalState<T>{},
293 "Reverse limit switch configuration requires both source and normal state");
294 config.HardwareLimitSwitch.ReverseLimitEnable = true;
295 }
296 config.HardwareLimitSwitch.ReverseLimitSource = T::reverseLimit_source;
297 }
298 if constexpr (has_reverseLimit_deviceID<T>{}) {
299 static_assert(has_reverseLimit_source<T>{} &&
300 T::reverseLimit_source != ctre::phoenix6::signals::ReverseLimitSourceValue::Disabled &&
301 T::reverseLimit_source != ctre::phoenix6::signals::ReverseLimitSourceValue::LimitSwitchPin,
302 "Reverse limit switch device ID has no effect when limit source is not remote");
303 config.HardwareLimitSwitch.ReverseLimitRemoteSensorID = T::reverseLimit_deviceID;
304 }
305 if constexpr (has_reverseLimit_normalState<T>{}) {
306 if constexpr (T::reverseLimit_normalState != ctre::phoenix6::signals::ReverseLimitSourceValue::Disabled) {
307 static_assert(has_reverseLimit_source<T>{}, "Reverse limit switch source required");
308 }
309 config.HardwareLimitSwitch.ReverseLimitType = T::reverseLimit_normalState;
310 }
311 } else {
312 config.HardwareLimitSwitch.ReverseLimitEnable = false;
313 }
314 if constexpr (has_neutralDeadband<T>{}) {
315 static_assert(T::neutralDeadband >= 0.001, "Neutral deadband must be greater than 0.001 (0.1%)");
316 static_assert(T::neutralDeadband <= 0.25, "Neutral deadband must be less than 0.25 (25%)");
317 config.MotorOutput.DutyCycleNeutralDeadband = T::neutralDeadband;
318 }
319
320 if constexpr (has_statusFrameMotorMode<T>()) {
321 argos_lib::status_frame_config::SetMotorStatusFrameRates(motorController, T::statusFrameMotorMode);
322 }
323
324 auto retVal = motorController.GetConfigurator().Apply(config, configTimeout);
325 if (0 != retVal) {
326 std::cout << "Error code (" << motorController.GetDeviceID() << "): " << retVal << '\n';
327 }
328
329 return 0 != retVal;
330 }
331
343 template <typename CompetitionConfig, typename PracticeConfig>
344 bool FalconConfig(ctre::phoenix6::hardware::TalonFX& motorController,
345 units::millisecond_t configTimeout,
346 argos_lib::RobotInstance instance) {
347 switch (instance) {
349 return FalconConfig<CompetitionConfig>(motorController, configTimeout);
350 break;
352 return FalconConfig<PracticeConfig>(motorController, configTimeout);
353 break;
354 }
355 return false;
356 }
357
358 } // namespace falcon_config
359} // namespace argos_lib
#define HAS_MEMBER(X)
Helper function generator to detect if a namespace has a member defined.
Definition compile_time_member_check.h:14
bool FalconConfig(ctre::phoenix6::hardware::TalonFX &motorController, units::millisecond_t configTimeout)
Configures a CTRE Falcon with only the fields provided. All other fields are given the factory defaul...
Definition falcon_config.h:123
void SetMotorStatusFrameRates(BaseTalon &motor, MotorPresetMode motorMode)
Set motor controller status frame update periods based on the motor preset.
Definition status_frame_config.cpp:9
Definition swap_controllers_command.h:12
RobotInstance
Differentiates between practice robot and competition robot.
Definition config_types.h:13
@ Competition
Competition robot.
@ Practice
Practice robot.
Definition custom_units.h:11
Definition falcon_config.h:24
Definition falcon_config.h:26
Definition falcon_config.h:39
Definition falcon_config.h:36
Definition falcon_config.h:40
Definition falcon_config.h:35
Definition falcon_config.h:34
Definition falcon_config.h:37
Definition falcon_config.h:38
Definition falcon_config.h:47
Definition falcon_config.h:44
Definition falcon_config.h:49
Definition falcon_config.h:43
Definition falcon_config.h:42
Definition falcon_config.h:45
Definition falcon_config.h:46