2022-Robot
Robot code for 2022 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
14#include "ctre/Phoenix.h"
15#include "status_frame_config.h"
16
17namespace argos_lib {
18 namespace falcon_config {
19
20 HAS_MEMBER(forwardLimit_deviceID)
21 HAS_MEMBER(forwardLimit_normalState)
22 HAS_MEMBER(forwardLimit_source)
23 HAS_MEMBER(inverted)
24 HAS_MEMBER(neutralDeadband)
25 HAS_MEMBER(neutralMode)
26 HAS_MEMBER(nominalOutputForward)
27 HAS_MEMBER(nominalOutputReverse)
28 HAS_MEMBER(peakOutputForward)
29 HAS_MEMBER(peakOutputReverse)
30 HAS_MEMBER(pid0_allowableError)
31 HAS_MEMBER(pid0_iZone)
32 HAS_MEMBER(pid0_kD)
33 HAS_MEMBER(pid0_kF)
34 HAS_MEMBER(pid0_kI)
35 HAS_MEMBER(pid0_kP)
36 HAS_MEMBER(pid0_selectedSensor)
37 HAS_MEMBER(pid1_allowableError)
38 HAS_MEMBER(pid1_iZone)
39 HAS_MEMBER(pid1_kD)
40 HAS_MEMBER(pid1_kF)
41 HAS_MEMBER(pid1_kI)
42 HAS_MEMBER(pid1_kP)
43 HAS_MEMBER(remoteFilter0_addr)
44 HAS_MEMBER(remoteFilter0_type)
45 HAS_MEMBER(reverseLimit_deviceID)
46 HAS_MEMBER(reverseLimit_normalState)
47 HAS_MEMBER(reverseLimit_source)
48 HAS_MEMBER(sensorPhase)
49 HAS_MEMBER(supplyCurrentLimit)
50 HAS_MEMBER(supplyCurrentThreshold)
51 HAS_MEMBER(supplyCurrentThresholdTime)
52 HAS_MEMBER(voltCompSat)
53 HAS_MEMBER(statusFrameMotorMode)
54
99 template <typename T>
100 bool FalconConfig(TalonFX& motorController, units::millisecond_t configTimeout) {
101 TalonFXConfiguration config;
102 auto timeout = configTimeout.to<int>();
103
104 if constexpr (has_inverted<T>{}) {
105 motorController.SetInverted(T::inverted);
106 }
107 if constexpr (has_sensorPhase<T>{}) {
108 motorController.SetSensorPhase(T::sensorPhase);
109 }
110 if constexpr (has_neutralMode<T>{}) {
111 motorController.SetNeutralMode(T::neutralMode);
112 }
113 if constexpr (has_voltCompSat<T>{}) {
114 constexpr units::volt_t voltage = T::voltCompSat;
115 config.voltageCompSaturation = voltage.to<double>();
116 motorController.EnableVoltageCompensation(true);
117 } else {
118 motorController.EnableVoltageCompensation(false);
119 }
121 ctre::phoenix::motorcontrol::can::FilterConfiguration filterConfig;
122 filterConfig.remoteSensorDeviceID = T::remoteFilter0_addr.address;
123 filterConfig.remoteSensorSource = T::remoteFilter0_type;
124 config.remoteFilter0 = filterConfig;
125 }
126 if constexpr (has_nominalOutputForward<T>{}) {
127 config.nominalOutputForward = T::nominalOutputForward;
128 }
129 if constexpr (has_nominalOutputReverse<T>{}) {
130 config.nominalOutputReverse = T::nominalOutputReverse;
131 }
132 if constexpr (has_peakOutputForward<T>{}) {
133 config.peakOutputForward = T::peakOutputForward;
134 }
135 if constexpr (has_peakOutputReverse<T>{}) {
136 config.peakOutputReverse = T::peakOutputReverse;
137 }
138 if constexpr (has_pid0_selectedSensor<T>{}) {
139 config.primaryPID.selectedFeedbackSensor = T::pid0_selectedSensor;
140 }
141 if constexpr (has_pid0_kP<T>{}) {
142 config.slot0.kP = T::pid0_kP;
143 }
144 if constexpr (has_pid0_kI<T>{}) {
145 config.slot0.kI = T::pid0_kI;
146 }
147 if constexpr (has_pid0_kD<T>{}) {
148 config.slot0.kD = T::pid0_kD;
149 }
150 if constexpr (has_pid0_kF<T>{}) {
151 config.slot0.kF = T::pid0_kF;
152 }
153 if constexpr (has_pid0_iZone<T>{}) {
154 config.slot0.integralZone = T::pid0_iZone;
155 }
156 if constexpr (has_pid0_allowableError<T>{}) {
157 config.slot0.allowableClosedloopError = T::pid0_allowableError;
158 }
159 if constexpr (has_pid1_kP<T>{}) {
160 config.slot1.kP = T::pid1_kP;
161 }
162 if constexpr (has_pid1_kI<T>{}) {
163 config.slot1.kI = T::pid1_kI;
164 }
165 if constexpr (has_pid1_kD<T>{}) {
166 config.slot1.kD = T::pid1_kD;
167 }
168 if constexpr (has_pid1_kF<T>{}) {
169 config.slot1.kF = T::pid1_kF;
170 }
171 if constexpr (has_pid1_iZone<T>{}) {
172 config.slot1.integralZone = T::pid1_iZone;
173 }
174 if constexpr (has_pid1_allowableError<T>{}) {
175 config.slot1.allowableClosedloopError = T::pid1_allowableError;
176 }
179 config.supplyCurrLimit.enable = true;
180 if constexpr (has_supplyCurrentLimit<T>{}) {
181 constexpr units::ampere_t currentLimit = T::supplyCurrentLimit;
182 static_assert(currentLimit.to<double>() > 0, "Current limit must be positive");
183 config.supplyCurrLimit.currentLimit = currentLimit.to<double>();
184 }
185 if constexpr (has_supplyCurrentThreshold<T>{}) {
186 constexpr units::ampere_t currentThreshold = T::supplyCurrentThreshold;
187 static_assert(currentThreshold.to<double>() > 0, "Current threshold must be positive");
188 config.supplyCurrLimit.triggerThresholdCurrent = currentThreshold.to<double>();
189 }
190 if constexpr (has_supplyCurrentThresholdTime<T>{}) {
191 constexpr units::second_t currentThresholdTime = T::supplyCurrentThresholdTime;
192 static_assert(currentThresholdTime.to<double>() >= 0, "Current threshold time must be non-negative");
193 config.supplyCurrLimit.triggerThresholdTime = currentThresholdTime.to<double>();
194 }
195 }
198 if constexpr (has_forwardLimit_source<T>{}) {
199 constexpr ctre::phoenix::motorcontrol::LimitSwitchSource source = T::forwardLimit_source;
200 if constexpr (source != ctre::phoenix::motorcontrol::LimitSwitchSource_Deactivated &&
201 source != ctre::phoenix::motorcontrol::LimitSwitchSource_FeedbackConnector) {
202 static_assert(has_forwardLimit_deviceID<T>{}, "Forward limit switch requires remote source device ID");
203 }
204 if constexpr (source != ctre::phoenix::motorcontrol::LimitSwitchSource_Deactivated) {
205 static_assert(has_forwardLimit_normalState<T>{} &&
206 T::forwardLimit_normalState != ctre::phoenix::motorcontrol::LimitSwitchNormal_Disabled,
207 "Forward limit switch configuration requires both source and normal state");
208 }
209 config.forwardLimitSwitchSource = T::forwardLimit_source;
210 }
211 if constexpr (has_forwardLimit_deviceID<T>{}) {
212 static_assert(has_forwardLimit_source<T>{} &&
213 T::forwardLimit_source != ctre::phoenix::motorcontrol::LimitSwitchSource_Deactivated &&
214 T::forwardLimit_source != ctre::phoenix::motorcontrol::LimitSwitchSource_FeedbackConnector,
215 "Forward limit switch device ID has no effect when limit source is not remote");
216 config.forwardLimitSwitchDeviceID = T::forwardLimit_deviceID;
217 }
218 if constexpr (has_forwardLimit_normalState<T>{}) {
219 if constexpr (T::forwardLimit_normalState != ctre::phoenix::motorcontrol::LimitSwitchNormal_Disabled) {
220 static_assert(has_forwardLimit_source<T>{}, "Forward limit switch source required");
221 }
222 config.forwardLimitSwitchNormal = T::forwardLimit_normalState;
223 }
224 }
227 if constexpr (has_reverseLimit_source<T>{}) {
228 constexpr ctre::phoenix::motorcontrol::LimitSwitchSource source = T::reverseLimit_source;
229 if constexpr (source != ctre::phoenix::motorcontrol::LimitSwitchSource_Deactivated &&
230 source != ctre::phoenix::motorcontrol::LimitSwitchSource_FeedbackConnector) {
231 static_assert(has_reverseLimit_deviceID<T>{}, "Reverse limit switch requires remote source device ID");
232 }
233 if constexpr (source != ctre::phoenix::motorcontrol::LimitSwitchSource_Deactivated) {
234 static_assert(has_reverseLimit_normalState<T>{} &&
235 T::reverseLimit_normalState != ctre::phoenix::motorcontrol::LimitSwitchNormal_Disabled,
236 "Reverse limit switch configuration requires both source and normal state");
237 }
238 config.reverseLimitSwitchSource = T::reverseLimit_source;
239 }
240 if constexpr (has_reverseLimit_deviceID<T>{}) {
241 static_assert(has_reverseLimit_source<T>{} &&
242 T::reverseLimit_source != ctre::phoenix::motorcontrol::LimitSwitchSource_Deactivated &&
243 T::reverseLimit_source != ctre::phoenix::motorcontrol::LimitSwitchSource_FeedbackConnector,
244 "Reverse limit switch device ID has no effect when limit source is not remote");
245 config.reverseLimitSwitchDeviceID = T::reverseLimit_deviceID;
246 }
247 if constexpr (has_reverseLimit_normalState<T>{}) {
248 if constexpr (T::reverseLimit_normalState != ctre::phoenix::motorcontrol::LimitSwitchNormal_Disabled) {
249 static_assert(has_reverseLimit_source<T>{}, "Reverse limit switch source required");
250 }
251 config.reverseLimitSwitchNormal = T::reverseLimit_normalState;
252 }
253 }
254 if constexpr (has_neutralDeadband<T>{}) {
255 static_assert(T::neutralDeadband >= 0.001, "Neutral deadband must be greater than 0.001 (0.1%)");
256 static_assert(T::neutralDeadband <= 0.25, "Neutral deadband must be less than 0.25 (25%)");
257 config.neutralDeadband = T::neutralDeadband;
258 }
259
260 if constexpr (has_statusFrameMotorMode<T>()) {
261 argos_lib::status_frame_config::SetMotorStatusFrameRates(motorController, T::statusFrameMotorMode);
262 }
263
264 auto retVal = motorController.ConfigAllSettings(config, timeout);
265 if (0 != retVal) {
266 std::cout << "Error code (" << motorController.GetDeviceID() << "): " << retVal << '\n';
267 }
268
269 return 0 != retVal;
270 }
271
283 template <typename CompetitionConfig, typename PracticeConfig>
284 bool FalconConfig(WPI_TalonFX& motorController,
285 units::millisecond_t configTimeout,
286 argos_lib::RobotInstance instance) {
287 switch (instance) {
289 return FalconConfig<CompetitionConfig>(motorController, configTimeout);
290 break;
292 return FalconConfig<PracticeConfig>(motorController, configTimeout);
293 break;
294 }
295 return false;
296 }
297
298 } // namespace falcon_config
299} // 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(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:100
void SetMotorStatusFrameRates(BaseTalon &motor, MotorPresetMode motorMode)
Set motor controller status frame update periods based on the motor preset.
Definition: status_frame_config.cpp:7
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: sensor_conversions.h:14
Definition: falcon_config.h:23
Definition: falcon_config.h:24
Definition: falcon_config.h:25
Definition: falcon_config.h:31
Definition: falcon_config.h:32
Definition: falcon_config.h:33
Definition: falcon_config.h:34
Definition: falcon_config.h:35
Definition: falcon_config.h:38
Definition: falcon_config.h:39
Definition: falcon_config.h:40
Definition: falcon_config.h:41
Definition: falcon_config.h:42
Definition: falcon_config.h:48
Definition: falcon_config.h:52