CTRE Phoenix C++ 5.33.1
Pigeon2.h
Go to the documentation of this file.
1/* Copyright (C) Cross The Road Electronics 2024 */
2/*
3 * Software License Agreement
4 *
5 * Copyright (C) Cross The Road Electronics. All rights
6 * reserved.
7 *
8 * Cross The Road Electronics (CTRE) licenses to you the right to
9 * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software
10 * API Libraries ONLY when in use with Cross The Road Electronics hardware products.
11 *
12 * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
13 * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT
14 * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A
15 * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL
16 * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL,
17 * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF
18 * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS
19 * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE
20 * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER
21 * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT
22 * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE
23 */
24
25#pragma once
26
27#include <string>
38
39namespace ctre {
40namespace phoenix {
41/** sensors namespace */
42namespace sensors {
43
44/**
45 * Configurables available to Pigeon
46 *
47 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
48 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
49 * Phoenix 6 API. A migration guide is available at
50 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
51 *
52 * If the Phoenix 5 API must be used for this device, the device must have 22.X
53 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
54 * the firmware year dropdown.
55 */
57 double MountPoseYaw {0};
58 double MountPosePitch {0};
59 double MountPoseRoll {0};
60 bool EnableCompass {false};
63 double XAxisGyroError{0};
64 double YAxisGyroError{0};
65 double ZAxisGyroError{0};
66
67 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
68 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
69 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
71
72 /**
73 * @return String representation of configs
74 */
75 std::string toString() {
76 return toString("");
77 }
78
79 /**
80 * @param prependString
81 * String to prepend to configs
82 * @return String representation of configs
83 */
84 std::string toString(std::string prependString) {
85 std::string retstr = CustomParamConfiguration::toString(prependString);
86
87 return retstr;
88 }
89};// struct Pigeon2
90
91/**
92 * Util class to help with Pigeon configurations
93 *
94 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
95 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
96 * Phoenix 6 API. A migration guide is available at
97 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
98 *
99 * If the Phoenix 5 API must be used for this device, the device must have 22.X
100 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
101 * the firmware year dropdown.
102 */
103struct [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
104 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
105 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
107private:
108 static Pigeon2Configuration _default;
109public:
110 /**
111 * Determine if specified value is different from default
112 * @param settings settings to compare against
113 * @return if specified value is different from default
114 * @{
115 */
116 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
117 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
118 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
119 static bool MountPoseYawDifferent (const Pigeon2Configuration & settings) { return (!(settings.MountPoseYaw == _default.MountPoseYaw)) || !settings.enableOptimizations; }
120 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
121 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
122 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
123 static bool MountPosePitchDifferent (const Pigeon2Configuration & settings) { return (!(settings.MountPosePitch == _default.MountPosePitch)) || !settings.enableOptimizations; }
124 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
125 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
126 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
127 static bool MountPoseRollDifferent(const Pigeon2Configuration & settings) { return (!(settings.MountPoseRoll == _default.MountPoseRoll)) || !settings.enableOptimizations; }
128 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
129 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
130 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
131 static bool EnableCompassDifferent(const Pigeon2Configuration & settings) { return (!(settings.EnableCompass == _default.EnableCompass)) || !settings.enableOptimizations; }
132 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
133 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
134 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
136 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
137 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
138 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
140 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
141 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
142 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
143 static bool XAxisGyroErrorDifferent(Pigeon2Configuration settings) { return (!(settings.XAxisGyroError == _default.XAxisGyroError)) || !settings.enableOptimizations; }
144 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
145 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
146 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
147 static bool YAxisGyroErrorDifferent(Pigeon2Configuration settings) { return (!(settings.YAxisGyroError == _default.YAxisGyroError)) || !settings.enableOptimizations; }
148 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
149 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
150 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
151 static bool ZAxisGyroErrorDifferent(Pigeon2Configuration settings) { return (!(settings.ZAxisGyroError == _default.ZAxisGyroError)) || !settings.enableOptimizations; }
152 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
153 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
154 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
155 static bool CustomParam0Different (const Pigeon2Configuration & settings) { return (!(settings.customParam0 == _default.customParam0)) || !settings.enableOptimizations; }
156 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
157 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
158 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
159 static bool CustomParam1Different (const Pigeon2Configuration & settings) { return (!(settings.customParam1 == _default.customParam1)) || !settings.enableOptimizations; }
160 /** @} */
161};
162
163/**
164 * Enumerations for what primary axis to talk about
165 * Positive indicates in n the direction, negative indicates in the opposite direction
166 *
167 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
168 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
169 * Phoenix 6 API. A migration guide is available at
170 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
171 *
172 * If the Phoenix 5 API must be used for this device, the device must have 22.X
173 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
174 * the firmware year dropdown.
175 */
176enum class [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
177 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
178 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
180 PositiveZ,
181 PositiveY,
182 PositiveX,
183 NegativeZ,
184 NegativeY,
185 NegativeX,
186};
187
188/**
189 * Pigeon 2 Class. Class supports communicating over CANbus.
190 *
191 * <pre>
192 * {@code
193 * // Example usage of a Pigeon 2
194 * Pigeon2 pigeon{0}; // creates a new Pigeon2 with ID 0
195 *
196 * Pigeon2Configuration config;
197 * // set mount pose as rolled 90 degrees counter-clockwise
198 * config.MountPoseYaw = 0;
199 * config.MountPosePitch = 0;
200 * config.MountPoseRoll = 90;
201 * pigeon.ConfigAllSettings(config);
202 *
203 * std::cout << pigeon.GetYaw() << std::endl; // prints the yaw of the Pigeon
204 * std::cout << pigeon.GetPitch() << std::endl; // prints the pitch of the Pigeon
205 * std::cout << pigeon.GetRoll() << std::endl; // prints the roll of the Pigeon
206 *
207 * double gravityVec[3];
208 * pigeon.GetGravityVector(gravityVec); // gets the gravity vector of the Pigeon 2
209 *
210 * ErrorCode error = pigeon.GetLastError(); // gets the last error generated by the Pigeon
211 * Pigeon2_Faults faults;
212 * ErrorCode faultsError = pigeon.GetFaults(faults); // fills faults with the current Pigeon 2 faults; returns the last error generated
213 * }
214 * </pre>
215 *
216 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
217 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
218 * Phoenix 6 API. A migration guide is available at
219 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
220 *
221 * If the Phoenix 5 API must be used for this device, the device must have 22.X
222 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
223 * the firmware year dropdown.
224 */
225class [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
226 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
227 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
228Pigeon2: public BasePigeon {
229public:
230 /**
231 * Create a Pigeon object that communicates with Pigeon on CAN Bus.
232 *
233 * @param deviceNumber
234 * CAN Device Id of Pigeon [0,62]
235 * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux),
236 * or a CANivore device name or serial number
237 */
238 Pigeon2(int deviceNumber, std::string const &canbus = "");
239 /**
240 * Gets the fault status
241 *
242 * @param toFill
243 * Container for fault statuses.
244 * @return Error Code generated by function. 0 indicates no error.
245 */
246 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
247 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
248 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
250 /**
251 * Gets the sticky fault status
252 *
253 * @param toFill
254 * Container for sticky fault statuses.
255 * @return Error Code generated by function. 0 indicates no error.
256 */
257 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
258 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
259 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
261
262 /**
263 * Configure the Mount Pose using the primary axis.
264 * This is useful if the Pigeon 2.0 is mounted straight, and you only
265 * need to describe what axis is forward and what axis is up.
266 *
267 * @param forward Axis that points forward from the robot
268 * @param up Axis that points up from the robot
269 * @param timeoutMs Config timeout in milliseconds.
270 * @return OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.
271 */
272 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
273 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
274 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
275 ErrorCode ConfigMountPose(AxisDirection forward, AxisDirection up, int timeoutMs = 50);
276
277 /**
278 * Configure the mounting pose of the Pigeon2.<p>
279 * This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current
280 * orientation, referenced from the robot's point of view.<p>
281 * This is only necessary if the Pigeon2 is mounted at an exotic angle
282 * near the gimbal lock point or not forward. <p>
283 * If the pigeon is relatively flat and pointed forward, this is not needed.<p>
284 * <p>
285 * Examples:<p>
286 * If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw,
287 * 0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.<p>
288 * If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it
289 * pitched 90 degrees clockwise. <p>
290 * @param yaw Yaw angle needed to reach the current orientation in degrees.
291 * @param pitch Pitch angle needed to reach the current orientation in degrees.
292 * @param roll Roll angle needed to reach the current orientation in degrees.
293 * @param timeoutMs Config timeout in milliseconds.
294 * @return Worst error code of all config sets.
295 */
296 ErrorCode ConfigMountPose(double yaw, double pitch, double roll, int timeoutMs = 0);
297 /**
298 * Configure the mounting pose Yaw of the Pigeon2.
299 * See {@link #configMountPose(double, double, double, int)}
300 *
301 * @param yaw Yaw angle needed to reach the current orientation in degrees.
302 * @param timeoutMs Config timeout in milliseconds.
303 * @return ErrorCode of configSet
304 */
305 ErrorCode ConfigMountPoseYaw(double yaw, int timeoutMs = 0);
306 /**
307 * Configure the mounting pose Pitch of the Pigeon2.
308 * See {@link #configMountPose(double, double, double, int)}
309 *
310 * @param pitch Pitch angle needed to reach the current orientation in degrees.
311 * @param timeoutMs Config timeout in milliseconds.
312 * @return ErrorCode of configSet
313 */
314 ErrorCode ConfigMountPosePitch(double pitch, int timeoutMs = 0);
315 /**
316 * Configure the mounting pose Roll of the Pigeon2.
317 * See {@link #configMountPose(double, double, double, int)}
318 *
319 * @param roll Roll angle needed to reach the current orientation in degrees.
320 * @param timeoutMs Config timeout in milliseconds.
321 * @return ErrorCode of configSet
322 */
323 ErrorCode ConfigMountPoseRoll(double roll, int timeoutMs = 0);
324 /**
325 * Configures the X Axis Gyroscope Error for 1 rotation
326 * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
327 * @param timeoutMs Config timeout in milliseconds.
328 * @return ErrorCode fo configSet
329 */
330 ErrorCode ConfigXAxisGyroError(double err, int timeoutMs = 0);
331 /**
332 * Configures the Y Axis Gyroscope Error for 1 rotation
333 * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
334 * @param timeoutMs Config timeout in milliseconds.
335 * @return ErrorCode fo configSet
336 */
337 ErrorCode ConfigYAxisGyroError(double err, int timeoutMs = 0);
338 /**
339 * Configures the Z Axis Gyroscope Error for 1 rotation
340 * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
341 * @param timeoutMs Config timeout in milliseconds.
342 * @return ErrorCode fo configSet
343 */
344 ErrorCode ConfigZAxisGyroError(double err, int timeoutMs = 0);
345
346 /**
347 * Enables the magnetometer fusion for Pigeon2. This is **not** recommended for FRC use
348 *
349 * @param enable Boolean to enable/disable magnetometer fusion
350 * @param timeoutMs
351 * Timeout value in ms. If nonzero, function will wait for
352 * config success and report an error if it times out.
353 * If zero, no blocking or checking is performed.
354 * @return ErrorCode Status of the config response
355 */
356 ErrorCode ConfigEnableCompass(bool enable, int timeoutMs = 0);
357 /**
358 * Disables temperature compensation from Pigeon2.
359 *
360 * @param disable Boolean to disable/enable temperature compensation
361 * @param timeoutMs
362 * Timeout value in ms. If nonzero, function will wait for
363 * config success and report an error if it times out.
364 * If zero, no blocking or checking is performed.
365 * @return ErrorCode Status of the config response
366 */
367 ErrorCode ConfigDisableTemperatureCompensation(bool disable, int timeoutMs = 0);
368 /**
369 * Disables the no-motion calibration from Pigeon2
370 *
371 * @param disable Boolean to disable/enable no-motion calibration
372 * @param timeoutMs
373 * Timeout value in ms. If nonzero, function will wait for
374 * config success and report an error if it times out.
375 * If zero, no blocking or checking is performed.
376 * @return ErrorCode Status of the config response
377 */
378 ErrorCode ConfigDisableNoMotionCalibration(bool disable, int timeoutMs = 0);
379
380 /**
381 * Performs an offset calibration on gyro bias
382 *
383 * @param timeoutMs
384 * Timeout value in ms. If nonzero, function will wait for
385 * config success and report an error if it times out.
386 * If zero, no blocking or checking is performed.
387 * @return ErrorCode Status of the config response
388 */
389 ErrorCode ZeroGyroBiasNow(int timeoutMs = 0);
390
391 /**
392 * Get the Gravity Vector.
393 *
394 * This provides a vector that points toward ground. This is useful for applications like
395 * an arm, where the z-value of the gravity vector corresponds to the feed-forward needed
396 * to hold the arm steady.
397 * The gravity vector is calculated after the mount pose, so if the pigeon is where it was
398 * mounted, the gravity vector is {0, 0, 1}.
399 * @param gravVector Pass in a double array of size 3 to get the gravity vector
400 * @return Errorcode of getter
401 */
402 ErrorCode GetGravityVector(double gravVector[3]) const;
403
404 /**
405 * Configures all persistent settings.
406 *
407 * @param allConfigs Object with all of the persistant settings
408 * @param timeoutMs
409 * Timeout value in ms. If nonzero, function will wait for
410 * config success and report an error if it times out.
411 * If zero, no blocking or checking is performed.
412 *
413 * @return Error Code generated by function. 0 indicates no error.
414 */
415 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
416 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
417 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
418 ErrorCode ConfigAllSettings(Pigeon2Configuration& settings, int timeoutMs = 50);
419 /**
420 * Gets all persistant settings.
421 *
422 * @param allConfigs Object with all of the persistant settings
423 * @param timeoutMs
424 * Timeout value in ms. If nonzero, function will wait for
425 * config success and report an error if it times out.
426 * If zero, no blocking or checking is performed.
427 */
428 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
429 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
430 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
431 void GetAllConfigs(Pigeon2Configuration& allConfigs, int timeoutMs = 50);
432
433};// class Pigeon2
434} // namespace signals
435} // namespace phoenix
436} // namespace ctre
Pigeon IMU Class.
Definition: BasePigeon.h:101
Pigeon 2 Class.
Definition: Pigeon2.h:228
ErrorCode ConfigZAxisGyroError(double err, int timeoutMs=0)
Configures the Z Axis Gyroscope Error for 1 rotation.
ErrorCode GetGravityVector(double gravVector[3]) const
Get the Gravity Vector.
ErrorCode ConfigEnableCompass(bool enable, int timeoutMs=0)
Enables the magnetometer fusion for Pigeon2.
ErrorCode ConfigDisableTemperatureCompensation(bool disable, int timeoutMs=0)
Disables temperature compensation from Pigeon2.
ErrorCode ZeroGyroBiasNow(int timeoutMs=0)
Performs an offset calibration on gyro bias.
ErrorCode ConfigDisableNoMotionCalibration(bool disable, int timeoutMs=0)
Disables the no-motion calibration from Pigeon2.
ErrorCode GetFaults(Pigeon2_Faults &toFill)
Gets the fault status.
ErrorCode ConfigYAxisGyroError(double err, int timeoutMs=0)
Configures the Y Axis Gyroscope Error for 1 rotation.
ErrorCode GetStickyFaults(Pigeon2_StickyFaults &toFill)
Gets the sticky fault status.
void GetAllConfigs(Pigeon2Configuration &allConfigs, int timeoutMs=50)
Gets all persistant settings.
ErrorCode ConfigXAxisGyroError(double err, int timeoutMs=0)
Configures the X Axis Gyroscope Error for 1 rotation.
ErrorCode ConfigMountPosePitch(double pitch, int timeoutMs=0)
Configure the mounting pose Pitch of the Pigeon2.
Pigeon2(int deviceNumber, std::string const &canbus="")
Create a Pigeon object that communicates with Pigeon on CAN Bus.
ErrorCode ConfigAllSettings(Pigeon2Configuration &settings, int timeoutMs=50)
Configures all persistent settings.
ErrorCode ConfigMountPose(AxisDirection forward, AxisDirection up, int timeoutMs=50)
Configure the Mount Pose using the primary axis.
ErrorCode ConfigMountPoseYaw(double yaw, int timeoutMs=0)
Configure the mounting pose Yaw of the Pigeon2.
ErrorCode ConfigMountPoseRoll(double roll, int timeoutMs=0)
Configure the mounting pose Roll of the Pigeon2.
ErrorCode ConfigMountPose(double yaw, double pitch, double roll, int timeoutMs=0)
Configure the mounting pose of the Pigeon2.
AxisDirection
Enumerations for what primary axis to talk about Positive indicates in n the direction,...
Definition: Pigeon2.h:179
ErrorCode
Definition: ErrorCode.h:13
namespace ctre
Definition: paramEnum.h:5
Configurables for any custom param configs.
Definition: CustomParamConfiguration.h:11
int customParam1
Custom Param 1.
Definition: CustomParamConfiguration.h:19
bool enableOptimizations
Enable optimizations for ConfigAll (defaults true)
Definition: CustomParamConfiguration.h:23
int customParam0
Custom Param 0.
Definition: CustomParamConfiguration.h:15
std::string toString()
Definition: CustomParamConfiguration.h:34
Sticky faults available to Pigeon.
Definition: Pigeon2_Faults.h:25
Sticky faults available to Pigeon.
Definition: Pigeon2_StickyFaults.h:25
Util class to help with Pigeon configurations.
Definition: Pigeon2.h:106
static bool DisableTemperatureCompensationDifferent(const Pigeon2Configuration &settings)
Definition: Pigeon2.h:135
static bool CustomParam1Different(const Pigeon2Configuration &settings)
Definition: Pigeon2.h:159
static bool ZAxisGyroErrorDifferent(Pigeon2Configuration settings)
Definition: Pigeon2.h:151
static bool MountPoseYawDifferent(const Pigeon2Configuration &settings)
Determine if specified value is different from default.
Definition: Pigeon2.h:119
static bool YAxisGyroErrorDifferent(Pigeon2Configuration settings)
Definition: Pigeon2.h:147
static bool EnableCompassDifferent(const Pigeon2Configuration &settings)
Definition: Pigeon2.h:131
static bool DisableNoMotionCalibrationDifferent(const Pigeon2Configuration &settings)
Definition: Pigeon2.h:139
static bool MountPosePitchDifferent(const Pigeon2Configuration &settings)
Definition: Pigeon2.h:123
static bool CustomParam0Different(const Pigeon2Configuration &settings)
Definition: Pigeon2.h:155
static bool XAxisGyroErrorDifferent(Pigeon2Configuration settings)
Definition: Pigeon2.h:143
static bool MountPoseRollDifferent(const Pigeon2Configuration &settings)
Definition: Pigeon2.h:127
Configurables available to Pigeon.
Definition: Pigeon2.h:56
bool EnableCompass
Definition: Pigeon2.h:60
bool DisableNoMotionCalibration
Definition: Pigeon2.h:62
std::string toString(std::string prependString)
Definition: Pigeon2.h:84
double ZAxisGyroError
Definition: Pigeon2.h:65
double YAxisGyroError
Definition: Pigeon2.h:64
std::string toString()
Definition: Pigeon2.h:75
Pigeon2Configuration()
Definition: Pigeon2.h:70
double XAxisGyroError
Definition: Pigeon2.h:63
bool DisableTemperatureCompensation
Definition: Pigeon2.h:61
double MountPoseYaw
Definition: Pigeon2.h:57
double MountPoseRoll
Definition: Pigeon2.h:59
double MountPosePitch
Definition: Pigeon2.h:58