Loading [MathJax]/extensions/tex2jax.js
CTRE Phoenix 6 C++ 23.10.0-alpha-8
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
CorePigeon2.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
12
14#include <units/acceleration.h>
15#include <units/angle.h>
16#include <units/angular_velocity.h>
17#include <units/dimensionless.h>
18#include <units/magnetic_field_strength.h>
19#include <units/temperature.h>
20#include <units/time.h>
21#include <units/voltage.h>
22
23namespace ctre {
24namespace phoenix6 {
25
26namespace hardware {
27namespace core {
28 class CorePigeon2;
29}
30}
31
32namespace configs {
33
34/**
35 * Class description for the Pigeon 2 IMU sensor that measures orientation.
36 *
37 * This handles the configurations for the hardware#Pigeon2
38 */
40{
41public:
42 /**
43 * \brief True if we should factory default newer unsupported configs,
44 * false to leave newer unsupported configs alone.
45 *
46 * \details This flag addresses a corner case where the device may have
47 * firmware with newer configs that didn't exist when this
48 * version of the API was built. If this occurs and this
49 * flag is true, unsupported new configs will be factory
50 * defaulted to avoid unexpected behavior.
51 *
52 * This is also the behavior in Phoenix 5, so this flag
53 * is defaulted to true to match.
54 */
56
57
58 /**
59 * \brief Configs for Pigeon 2's Mount Pose configuration.
60 *
61 * \details These configs allow the Pigeon2 to be mounted in whatever
62 * orientation that's desired and ensure the reported
63 * Yaw/Pitch/Roll is from the robot's reference.
64 */
66
67 /**
68 * \brief Configs to trim the Pigeon2's gyroscope.
69 *
70 * \details Pigeon2 allows the user to trim the gyroscope's
71 * sensitivity. While this isn't necessary for the Pigeon2,
72 * as it comes calibrated out-of-the-box, users can make use
73 * of this to make the Pigeon2 even more accurate for their
74 * application.
75 */
77
78 /**
79 * \brief Configs to enable/disable various features of the Pigeon2.
80 *
81 * \details These configs allow the user to enable or disable various
82 * aspects of the Pigeon2.
83 */
85
86 /**
87 * \brief Get the string representation of this configuration
88 */
89 std::string ToString() const
90 {
91 std::stringstream ss;
92 ss << MountPose.ToString();
93 ss << GyroTrim.ToString();
95 return ss.str();
96 }
97
98 /**
99 * \brief Get the serialized form of this configuration
100 */
101 std::string Serialize() const
102 {
103 std::stringstream ss;
104 ss << MountPose.Serialize();
105 ss << GyroTrim.Serialize();
107 return ss.str();
108 }
109
110 /**
111 * \brief Take a string and deserialize it to this configuration
112 */
113 ctre::phoenix::StatusCode Deserialize(const std::string& to_deserialize)
114 {
115 ctre::phoenix::StatusCode err = ctre::phoenix::StatusCode::OK;
116 err = MountPose.Deserialize(to_deserialize);
117 err = GyroTrim.Deserialize(to_deserialize);
118 err = Pigeon2Features.Deserialize(to_deserialize);
119 return err;
120 }
121};
122
123/**
124 * Class description for the Pigeon 2 IMU sensor that measures orientation.
125 *
126 * This handles the configurations for the hardware#Pigeon2
127 */
129{
131 ParentConfigurator{std::move(id)}
132 {}
133
135public:
136
137 /**
138 * Delete the copy constructor, we can only pass by reference
139 */
141
142 /**
143 * \brief Refreshes the values of the specified config group.
144 *
145 * This will wait up to #defaultTimeoutSeconds.
146 *
147 * \details Call to refresh the selected configs from the device.
148 *
149 * \param configs The configs to refresh
150 * \returns StatusCode of refreshing the configs
151 */
152 ctre::phoenix::StatusCode Refresh(Pigeon2Configuration& configs) const
153 {
154 return Refresh(configs, defaultTimeoutSeconds);
155 }
156
157 /**
158 * \brief Refreshes the values of the specified config group.
159 *
160 * \details Call to refresh the selected configs from the device.
161 *
162 * \param configs The configs to refresh
163 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
164 * \returns StatusCode of refreshing the configs
165 */
166 ctre::phoenix::StatusCode Refresh(Pigeon2Configuration& configs, units::time::second_t timeoutSeconds) const
167 {
168 std::string ref;
169 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
170 configs.Deserialize(ref);
171 return ret;
172 }
173
174 /**
175 * \brief Applies the contents of the specified config to the device.
176 *
177 * This will wait up to #defaultTimeoutSeconds.
178 *
179 * \details Call to apply the selected configs.
180 *
181 * \param configs Configs to apply against.
182 * \returns StatusCode of the set command
183 */
184 ctre::phoenix::StatusCode Apply(const Pigeon2Configuration& configs)
185 {
186 return Apply(configs, defaultTimeoutSeconds);
187 }
188
189 /**
190 * \brief Applies the contents of the specified config to the device.
191 *
192 * \details Call to apply the selected configs.
193 *
194 * \param configs Configs to apply against.
195 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
196 * \returns StatusCode of the set command
197 */
198 ctre::phoenix::StatusCode Apply(const Pigeon2Configuration& configs, units::time::second_t timeoutSeconds)
199 {
200 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, configs.FutureProofConfigs, false);
201 }
202
203
204 /**
205 * \brief Refreshes the values of the specified config group.
206 *
207 * This will wait up to #defaultTimeoutSeconds.
208 *
209 * \details Call to refresh the selected configs from the device.
210 *
211 * \param configs The configs to refresh
212 * \returns StatusCode of refreshing the configs
213 */
214 ctre::phoenix::StatusCode Refresh(MountPoseConfigs& configs) const
215 {
216 return Refresh(configs, defaultTimeoutSeconds);
217 }
218 /**
219 * \brief Refreshes the values of the specified config group.
220 *
221 * \details Call to refresh the selected configs from the device.
222 *
223 * \param configs The configs to refresh
224 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
225 * \returns StatusCode of refreshing the configs
226 */
227 ctre::phoenix::StatusCode Refresh(MountPoseConfigs& configs, units::time::second_t timeoutSeconds) const
228 {
229 std::string ref;
230 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
231 configs.Deserialize(ref);
232 return ret;
233 }
234
235 /**
236 * \brief Applies the contents of the specified config to the device.
237 *
238 * This will wait up to #defaultTimeoutSeconds.
239 *
240 * \details Call to apply the selected configs.
241 *
242 * \param configs Configs to apply against.
243 * \returns StatusCode of the set command
244 */
245 ctre::phoenix::StatusCode Apply(const MountPoseConfigs& configs)
246 {
247 return Apply(configs, defaultTimeoutSeconds);
248 }
249
250 /**
251 * \brief Applies the contents of the specified config to the device.
252 *
253 * \details Call to apply the selected configs.
254 *
255 * \param configs Configs to apply against.
256 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
257 * \returns StatusCode of the set command
258 */
259 ctre::phoenix::StatusCode Apply(const MountPoseConfigs& configs, units::time::second_t timeoutSeconds)
260 {
261 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
262 }
263
264 /**
265 * \brief Refreshes the values of the specified config group.
266 *
267 * This will wait up to #defaultTimeoutSeconds.
268 *
269 * \details Call to refresh the selected configs from the device.
270 *
271 * \param configs The configs to refresh
272 * \returns StatusCode of refreshing the configs
273 */
274 ctre::phoenix::StatusCode Refresh(GyroTrimConfigs& configs) const
275 {
276 return Refresh(configs, defaultTimeoutSeconds);
277 }
278 /**
279 * \brief Refreshes the values of the specified config group.
280 *
281 * \details Call to refresh the selected configs from the device.
282 *
283 * \param configs The configs to refresh
284 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
285 * \returns StatusCode of refreshing the configs
286 */
287 ctre::phoenix::StatusCode Refresh(GyroTrimConfigs& configs, units::time::second_t timeoutSeconds) const
288 {
289 std::string ref;
290 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
291 configs.Deserialize(ref);
292 return ret;
293 }
294
295 /**
296 * \brief Applies the contents of the specified config to the device.
297 *
298 * This will wait up to #defaultTimeoutSeconds.
299 *
300 * \details Call to apply the selected configs.
301 *
302 * \param configs Configs to apply against.
303 * \returns StatusCode of the set command
304 */
305 ctre::phoenix::StatusCode Apply(const GyroTrimConfigs& configs)
306 {
307 return Apply(configs, defaultTimeoutSeconds);
308 }
309
310 /**
311 * \brief Applies the contents of the specified config to the device.
312 *
313 * \details Call to apply the selected configs.
314 *
315 * \param configs Configs to apply against.
316 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
317 * \returns StatusCode of the set command
318 */
319 ctre::phoenix::StatusCode Apply(const GyroTrimConfigs& configs, units::time::second_t timeoutSeconds)
320 {
321 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
322 }
323
324 /**
325 * \brief Refreshes the values of the specified config group.
326 *
327 * This will wait up to #defaultTimeoutSeconds.
328 *
329 * \details Call to refresh the selected configs from the device.
330 *
331 * \param configs The configs to refresh
332 * \returns StatusCode of refreshing the configs
333 */
334 ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs& configs) const
335 {
336 return Refresh(configs, defaultTimeoutSeconds);
337 }
338 /**
339 * \brief Refreshes the values of the specified config group.
340 *
341 * \details Call to refresh the selected configs from the device.
342 *
343 * \param configs The configs to refresh
344 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
345 * \returns StatusCode of refreshing the configs
346 */
347 ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs& configs, units::time::second_t timeoutSeconds) const
348 {
349 std::string ref;
350 ctre::phoenix::StatusCode ret = GetConfigsPrivate(ref, timeoutSeconds);
351 configs.Deserialize(ref);
352 return ret;
353 }
354
355 /**
356 * \brief Applies the contents of the specified config to the device.
357 *
358 * This will wait up to #defaultTimeoutSeconds.
359 *
360 * \details Call to apply the selected configs.
361 *
362 * \param configs Configs to apply against.
363 * \returns StatusCode of the set command
364 */
365 ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs& configs)
366 {
367 return Apply(configs, defaultTimeoutSeconds);
368 }
369
370 /**
371 * \brief Applies the contents of the specified config to the device.
372 *
373 * \details Call to apply the selected configs.
374 *
375 * \param configs Configs to apply against.
376 * \param timeoutSeconds Maximum amount of time to wait when performing configuration
377 * \returns StatusCode of the set command
378 */
379 ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs& configs, units::time::second_t timeoutSeconds)
380 {
381 return SetConfigsPrivate(configs.Serialize(), timeoutSeconds, false, false);
382 }
383
384
385 /**
386 * \brief The yaw to set the Pigeon2 to right now.
387 *
388 * This will wait up to #defaultTimeoutSeconds.
389 *
390 * This is available in the configurator in case the user wants
391 * to initialize their device entirely without passing a device
392 * reference down to the code that performs the initialization.
393 * In this case, the user passes down the configurator object
394 * and performs all the initialization code on the object.
395 *
396 * \param newValue Value to set to. Units are in deg.
397 * \returns StatusCode of the set command
398 */
399 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
400 {
401 return SetYaw(newValue, defaultTimeoutSeconds);
402 }
403 /**
404 * \brief The yaw to set the Pigeon2 to right now.
405 *
406 * This is available in the configurator in case the user wants
407 * to initialize their device entirely without passing a device
408 * reference down to the code that performs the initialization.
409 * In this case, the user passes down the configurator object
410 * and performs all the initialization code on the object.
411 *
412 * \param newValue Value to set to. Units are in deg.
413 * \param timeoutSeconds Maximum time to wait up to in seconds.
414 * \returns StatusCode of the set command
415 */
416 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
417 {
418 std::stringstream ss;
419 char *ref;
420 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2_SetYaw, newValue.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
421 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
422 }
423
424 /**
425 * \brief Clear the sticky faults in the device.
426 *
427 * \details This typically has no impact on the device functionality.
428 * Instead, it just clears telemetry faults that are accessible via
429 * API and Tuner Self-Test.
430 *
431 * This will wait up to #defaultTimeoutSeconds.
432 *
433 * This is available in the configurator in case the user wants
434 * to initialize their device entirely without passing a device
435 * reference down to the code that performs the initialization.
436 * In this case, the user passes down the configurator object
437 * and performs all the initialization code on the object.
438 * \returns StatusCode of the set command
439 */
440 ctre::phoenix::StatusCode ClearStickyFaults()
441 {
443 }
444 /**
445 * \brief Clear the sticky faults in the device.
446 *
447 * \details This typically has no impact on the device functionality.
448 * Instead, it just clears telemetry faults that are accessible via
449 * API and Tuner Self-Test.
450 *
451 * This is available in the configurator in case the user wants
452 * to initialize their device entirely without passing a device
453 * reference down to the code that performs the initialization.
454 * In this case, the user passes down the configurator object
455 * and performs all the initialization code on the object.
456 * \param timeoutSeconds Maximum time to wait up to in seconds.
457 * \returns StatusCode of the set command
458 */
459 ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
460 {
461 std::stringstream ss;
462 char *ref;
463 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::SPN_ClearStickyFaults, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
464 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
465 }
466
467 /**
468 * \brief Clear sticky fault: Hardware fault occurred
469 *
470 * This will wait up to #defaultTimeoutSeconds.
471 *
472 * This is available in the configurator in case the user wants
473 * to initialize their device entirely without passing a device
474 * reference down to the code that performs the initialization.
475 * In this case, the user passes down the configurator object
476 * and performs all the initialization code on the object.
477 * \returns StatusCode of the set command
478 */
479 ctre::phoenix::StatusCode ClearStickyFault_Hardware()
480 {
482 }
483 /**
484 * \brief Clear sticky fault: Hardware fault occurred
485 *
486 * This is available in the configurator in case the user wants
487 * to initialize their device entirely without passing a device
488 * reference down to the code that performs the initialization.
489 * In this case, the user passes down the configurator object
490 * and performs all the initialization code on the object.
491 * \param timeoutSeconds Maximum time to wait up to in seconds.
492 * \returns StatusCode of the set command
493 */
494 ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
495 {
496 std::stringstream ss;
497 char *ref;
498 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_Hardware, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
499 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
500 }
501
502 /**
503 * \brief Clear sticky fault: Device supply voltage dropped to near
504 * brownout levels
505 *
506 * This will wait up to #defaultTimeoutSeconds.
507 *
508 * This is available in the configurator in case the user wants
509 * to initialize their device entirely without passing a device
510 * reference down to the code that performs the initialization.
511 * In this case, the user passes down the configurator object
512 * and performs all the initialization code on the object.
513 * \returns StatusCode of the set command
514 */
515 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
516 {
518 }
519 /**
520 * \brief Clear sticky fault: Device supply voltage dropped to near
521 * brownout levels
522 *
523 * This is available in the configurator in case the user wants
524 * to initialize their device entirely without passing a device
525 * reference down to the code that performs the initialization.
526 * In this case, the user passes down the configurator object
527 * and performs all the initialization code on the object.
528 * \param timeoutSeconds Maximum time to wait up to in seconds.
529 * \returns StatusCode of the set command
530 */
531 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
532 {
533 std::stringstream ss;
534 char *ref;
535 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_Undervoltage, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
536 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
537 }
538
539 /**
540 * \brief Clear sticky fault: Device boot while detecting the enable
541 * signal
542 *
543 * This will wait up to #defaultTimeoutSeconds.
544 *
545 * This is available in the configurator in case the user wants
546 * to initialize their device entirely without passing a device
547 * reference down to the code that performs the initialization.
548 * In this case, the user passes down the configurator object
549 * and performs all the initialization code on the object.
550 * \returns StatusCode of the set command
551 */
552 ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
553 {
555 }
556 /**
557 * \brief Clear sticky fault: Device boot while detecting the enable
558 * signal
559 *
560 * This is available in the configurator in case the user wants
561 * to initialize their device entirely without passing a device
562 * reference down to the code that performs the initialization.
563 * In this case, the user passes down the configurator object
564 * and performs all the initialization code on the object.
565 * \param timeoutSeconds Maximum time to wait up to in seconds.
566 * \returns StatusCode of the set command
567 */
568 ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
569 {
570 std::stringstream ss;
571 char *ref;
572 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_BootDuringEnable, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
573 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
574 }
575
576 /**
577 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
578 *
579 * This will wait up to #defaultTimeoutSeconds.
580 *
581 * This is available in the configurator in case the user wants
582 * to initialize their device entirely without passing a device
583 * reference down to the code that performs the initialization.
584 * In this case, the user passes down the configurator object
585 * and performs all the initialization code on the object.
586 * \returns StatusCode of the set command
587 */
588 ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
589 {
591 }
592 /**
593 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
594 *
595 * This is available in the configurator in case the user wants
596 * to initialize their device entirely without passing a device
597 * reference down to the code that performs the initialization.
598 * In this case, the user passes down the configurator object
599 * and performs all the initialization code on the object.
600 * \param timeoutSeconds Maximum time to wait up to in seconds.
601 * \returns StatusCode of the set command
602 */
603 ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
604 {
605 std::stringstream ss;
606 char *ref;
607 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_BootupAccel, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
608 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
609 }
610
611 /**
612 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
613 *
614 * This will wait up to #defaultTimeoutSeconds.
615 *
616 * This is available in the configurator in case the user wants
617 * to initialize their device entirely without passing a device
618 * reference down to the code that performs the initialization.
619 * In this case, the user passes down the configurator object
620 * and performs all the initialization code on the object.
621 * \returns StatusCode of the set command
622 */
623 ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
624 {
626 }
627 /**
628 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
629 *
630 * This is available in the configurator in case the user wants
631 * to initialize their device entirely without passing a device
632 * reference down to the code that performs the initialization.
633 * In this case, the user passes down the configurator object
634 * and performs all the initialization code on the object.
635 * \param timeoutSeconds Maximum time to wait up to in seconds.
636 * \returns StatusCode of the set command
637 */
638 ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
639 {
640 std::stringstream ss;
641 char *ref;
642 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_BootupGyros, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
643 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
644 }
645
646 /**
647 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
648 *
649 * This will wait up to #defaultTimeoutSeconds.
650 *
651 * This is available in the configurator in case the user wants
652 * to initialize their device entirely without passing a device
653 * reference down to the code that performs the initialization.
654 * In this case, the user passes down the configurator object
655 * and performs all the initialization code on the object.
656 * \returns StatusCode of the set command
657 */
658 ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
659 {
661 }
662 /**
663 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
664 *
665 * This is available in the configurator in case the user wants
666 * to initialize their device entirely without passing a device
667 * reference down to the code that performs the initialization.
668 * In this case, the user passes down the configurator object
669 * and performs all the initialization code on the object.
670 * \param timeoutSeconds Maximum time to wait up to in seconds.
671 * \returns StatusCode of the set command
672 */
673 ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
674 {
675 std::stringstream ss;
676 char *ref;
677 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_BootupMagne, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
678 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
679 }
680
681 /**
682 * \brief Clear sticky fault: Motion Detected during bootup.
683 *
684 * This will wait up to #defaultTimeoutSeconds.
685 *
686 * This is available in the configurator in case the user wants
687 * to initialize their device entirely without passing a device
688 * reference down to the code that performs the initialization.
689 * In this case, the user passes down the configurator object
690 * and performs all the initialization code on the object.
691 * \returns StatusCode of the set command
692 */
693 ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
694 {
696 }
697 /**
698 * \brief Clear sticky fault: Motion Detected during bootup.
699 *
700 * This is available in the configurator in case the user wants
701 * to initialize their device entirely without passing a device
702 * reference down to the code that performs the initialization.
703 * In this case, the user passes down the configurator object
704 * and performs all the initialization code on the object.
705 * \param timeoutSeconds Maximum time to wait up to in seconds.
706 * \returns StatusCode of the set command
707 */
708 ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
709 {
710 std::stringstream ss;
711 char *ref;
712 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_BootIntoMotion, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
713 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
714 }
715
716 /**
717 * \brief Clear sticky fault: Motion stack data acquisition was slower
718 * than expected
719 *
720 * This will wait up to #defaultTimeoutSeconds.
721 *
722 * This is available in the configurator in case the user wants
723 * to initialize their device entirely without passing a device
724 * reference down to the code that performs the initialization.
725 * In this case, the user passes down the configurator object
726 * and performs all the initialization code on the object.
727 * \returns StatusCode of the set command
728 */
729 ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
730 {
732 }
733 /**
734 * \brief Clear sticky fault: Motion stack data acquisition was slower
735 * than expected
736 *
737 * This is available in the configurator in case the user wants
738 * to initialize their device entirely without passing a device
739 * reference down to the code that performs the initialization.
740 * In this case, the user passes down the configurator object
741 * and performs all the initialization code on the object.
742 * \param timeoutSeconds Maximum time to wait up to in seconds.
743 * \returns StatusCode of the set command
744 */
745 ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
746 {
747 std::stringstream ss;
748 char *ref;
749 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_DataAcquiredLate, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
750 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
751 }
752
753 /**
754 * \brief Clear sticky fault: Motion stack loop time was slower than
755 * expected.
756 *
757 * This will wait up to #defaultTimeoutSeconds.
758 *
759 * This is available in the configurator in case the user wants
760 * to initialize their device entirely without passing a device
761 * reference down to the code that performs the initialization.
762 * In this case, the user passes down the configurator object
763 * and performs all the initialization code on the object.
764 * \returns StatusCode of the set command
765 */
766 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
767 {
769 }
770 /**
771 * \brief Clear sticky fault: Motion stack loop time was slower than
772 * expected.
773 *
774 * This is available in the configurator in case the user wants
775 * to initialize their device entirely without passing a device
776 * reference down to the code that performs the initialization.
777 * In this case, the user passes down the configurator object
778 * and performs all the initialization code on the object.
779 * \param timeoutSeconds Maximum time to wait up to in seconds.
780 * \returns StatusCode of the set command
781 */
782 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
783 {
784 std::stringstream ss;
785 char *ref;
786 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_LoopTimeSlow, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
787 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
788 }
789
790 /**
791 * \brief Clear sticky fault: Magnetometer values are saturated
792 *
793 * This will wait up to #defaultTimeoutSeconds.
794 *
795 * This is available in the configurator in case the user wants
796 * to initialize their device entirely without passing a device
797 * reference down to the code that performs the initialization.
798 * In this case, the user passes down the configurator object
799 * and performs all the initialization code on the object.
800 * \returns StatusCode of the set command
801 */
802 ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
803 {
805 }
806 /**
807 * \brief Clear sticky fault: Magnetometer values are saturated
808 *
809 * This is available in the configurator in case the user wants
810 * to initialize their device entirely without passing a device
811 * reference down to the code that performs the initialization.
812 * In this case, the user passes down the configurator object
813 * and performs all the initialization code on the object.
814 * \param timeoutSeconds Maximum time to wait up to in seconds.
815 * \returns StatusCode of the set command
816 */
817 ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
818 {
819 std::stringstream ss;
820 char *ref;
821 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_SaturatedMagne, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
822 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
823 }
824
825 /**
826 * \brief Clear sticky fault: Accelerometer values are saturated
827 *
828 * This will wait up to #defaultTimeoutSeconds.
829 *
830 * This is available in the configurator in case the user wants
831 * to initialize their device entirely without passing a device
832 * reference down to the code that performs the initialization.
833 * In this case, the user passes down the configurator object
834 * and performs all the initialization code on the object.
835 * \returns StatusCode of the set command
836 */
837 ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer()
838 {
840 }
841 /**
842 * \brief Clear sticky fault: Accelerometer values are saturated
843 *
844 * This is available in the configurator in case the user wants
845 * to initialize their device entirely without passing a device
846 * reference down to the code that performs the initialization.
847 * In this case, the user passes down the configurator object
848 * and performs all the initialization code on the object.
849 * \param timeoutSeconds Maximum time to wait up to in seconds.
850 * \returns StatusCode of the set command
851 */
852 ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer(units::time::second_t timeoutSeconds)
853 {
854 std::stringstream ss;
855 char *ref;
856 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_SaturatedAccel, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
857 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
858 }
859
860 /**
861 * \brief Clear sticky fault: Gyroscope values are saturated
862 *
863 * This will wait up to #defaultTimeoutSeconds.
864 *
865 * This is available in the configurator in case the user wants
866 * to initialize their device entirely without passing a device
867 * reference down to the code that performs the initialization.
868 * In this case, the user passes down the configurator object
869 * and performs all the initialization code on the object.
870 * \returns StatusCode of the set command
871 */
872 ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
873 {
875 }
876 /**
877 * \brief Clear sticky fault: Gyroscope values are saturated
878 *
879 * This is available in the configurator in case the user wants
880 * to initialize their device entirely without passing a device
881 * reference down to the code that performs the initialization.
882 * In this case, the user passes down the configurator object
883 * and performs all the initialization code on the object.
884 * \param timeoutSeconds Maximum time to wait up to in seconds.
885 * \returns StatusCode of the set command
886 */
887 ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
888 {
889 std::stringstream ss;
890 char *ref;
891 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::ClearStickyFault_PIGEON2_SaturatedGyros, 0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
892 return SetConfigsPrivate(ss.str(), timeoutSeconds, false, true);
893 }
894};
895
896}
897
898namespace hardware {
899namespace core {
900
901/**
902 * Class description for the Pigeon 2 IMU sensor that measures orientation.
903 */
905{
906private:
908
909 bool _isInitialized = false;
910 bool _isVersionOk = false;
911 StatusSignal<int> &_compliancy{LookupStatusSignal<int>(ctre::phoenix6::spns::SpnValue::Compliancy_Version, "Compliancy", false)};
912 double _timeToRefreshVersion = GetCurrentTimeSeconds();
913
914 StatusSignal<int> &_resetSignal{LookupStatusSignal<int>(ctre::phoenix6::spns::SpnValue::Startup_ResetFlags, "ResetFlags", false)};
915
916 double _creationTime = GetCurrentTimeSeconds();
917
918 void ReportIfTooOld() override;
919
920
921public:
922 /**
923 * Constructs a new Pigeon 2 sensor object.
924 *
925 * \param deviceId ID of the device, as configured in Phoenix Tuner.
926 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
927 * - "rio" for the native roboRIO CAN bus
928 * - CANivore name or serial number
929 * - SocketCAN interface (non-FRC Linux only)
930 * - "*" for any CANivore seen by the program
931 * - empty string (default) to select the default for the system:
932 * - "rio" on roboRIO
933 * - "can0" on Linux
934 * - "*" on Windows
935 */
936 CorePigeon2(int deviceId, std::string canbus = "");
937
938 CorePigeon2(CorePigeon2 const &) = delete;
940
941 /**
942 * \returns true if device has reset since the previous call of this routine.
943 */
945 {
946 return _resetSignal.Refresh(false).HasUpdated();
947 }
948
949 /**
950 * \returns a function that checks for device resets.
951 */
952 std::function<bool()> GetResetOccurredChecker() const
953 {
954 return [resetSignal=_resetSignal]() mutable {
955 return resetSignal.Refresh(false).HasUpdated();
956 };
957 }
958
959 /**
960 * \brief Gets the configurator for this Pigeon2
961 *
962 * \details Gets the configurator for this Pigeon2
963 *
964 * \returns Configurator for this Pigeon2
965 */
967 {
968 return _configs;
969 }
970
971 /**
972 * \brief Gets the configurator for this Pigeon2
973 *
974 * \details Gets the configurator for this Pigeon2
975 *
976 * \returns Configurator for this Pigeon2
977 */
979 {
980 return _configs;
981 }
982
983
984private:
985 std::unique_ptr<sim::Pigeon2SimState> _simState{};
986public:
987 /**
988 * \brief Get the simulation state for this device.
989 *
990 * \details This function reuses an allocated simulation
991 * state object, so it is safe to call this function multiple
992 * times in a robot loop.
993 *
994 * \returns Simulation state
995 */
997 {
998 if (_simState == nullptr)
999 _simState = std::make_unique<sim::Pigeon2SimState>(*this);
1000 return *_simState;
1001 }
1002
1003
1004
1005 /**
1006 * \brief App Major Version number.
1007 *
1008 * Minimum Value: 0
1009 * Maximum Value: 255
1010 * Default Value: 0
1011 * Units:
1012 *
1013 * Default Rates:
1014 * CAN: 4.0 Hz
1015 *
1016 * \returns VersionMajor Status Signal Object
1017 */
1019
1020 /**
1021 * \brief App Minor Version number.
1022 *
1023 * Minimum Value: 0
1024 * Maximum Value: 255
1025 * Default Value: 0
1026 * Units:
1027 *
1028 * Default Rates:
1029 * CAN: 4.0 Hz
1030 *
1031 * \returns VersionMinor Status Signal Object
1032 */
1034
1035 /**
1036 * \brief App Bugfix Version number.
1037 *
1038 * Minimum Value: 0
1039 * Maximum Value: 255
1040 * Default Value: 0
1041 * Units:
1042 *
1043 * Default Rates:
1044 * CAN: 4.0 Hz
1045 *
1046 * \returns VersionBugfix Status Signal Object
1047 */
1049
1050 /**
1051 * \brief App Build Version number.
1052 *
1053 * Minimum Value: 0
1054 * Maximum Value: 255
1055 * Default Value: 0
1056 * Units:
1057 *
1058 * Default Rates:
1059 * CAN: 4.0 Hz
1060 *
1061 * \returns VersionBuild Status Signal Object
1062 */
1064
1065 /**
1066 * \brief Full Version. The format is a four byte value.
1067 *
1068 * \details Full Version of firmware in device. The format is a four
1069 * byte value.
1070 *
1071 * Minimum Value: 0
1072 * Maximum Value: 4294967295
1073 * Default Value: 0
1074 * Units:
1075 *
1076 * Default Rates:
1077 * CAN: 4.0 Hz
1078 *
1079 * \returns Version Status Signal Object
1080 */
1082
1083 /**
1084 * \brief Integer representing all faults
1085 *
1086 * \details This returns the fault flags reported by the device. These
1087 * are device specific and are not used directly in typical
1088 * applications. Use the signal specific GetFault_*() methods instead.
1089 *
1090 *
1091 * Minimum Value: 0
1092 * Maximum Value: 16777215
1093 * Default Value: 0
1094 * Units:
1095 *
1096 * Default Rates:
1097 * CAN: 4.0 Hz
1098 *
1099 * \returns FaultField Status Signal Object
1100 */
1102
1103 /**
1104 * \brief Integer representing all sticky faults
1105 *
1106 * \details This returns the persistent "sticky" fault flags reported
1107 * by the device. These are device specific and are not used directly
1108 * in typical applications. Use the signal specific GetStickyFault_*()
1109 * methods instead.
1110 *
1111 * Minimum Value: 0
1112 * Maximum Value: 16777215
1113 * Default Value: 0
1114 * Units:
1115 *
1116 * Default Rates:
1117 * CAN: 4.0 Hz
1118 *
1119 * \returns StickyFaultField Status Signal Object
1120 */
1122
1123 /**
1124 * \brief Current reported yaw of the Pigeon2.
1125 *
1126 * Minimum Value: -368640.0
1127 * Maximum Value: 368639.99725341797
1128 * Default Value: 0
1129 * Units: deg
1130 *
1131 * Default Rates:
1132 * CAN: 100.0 Hz
1133 *
1134 * \returns Yaw Status Signal Object
1135 */
1137
1138 /**
1139 * \brief Current reported pitch of the Pigeon2.
1140 *
1141 * Minimum Value: -90.0
1142 * Maximum Value: 89.9560546875
1143 * Default Value: 0
1144 * Units: deg
1145 *
1146 * Default Rates:
1147 * CAN: 100.0 Hz
1148 *
1149 * \returns Pitch Status Signal Object
1150 */
1152
1153 /**
1154 * \brief Current reported roll of the Pigeon2.
1155 *
1156 * Minimum Value: -180.0
1157 * Maximum Value: 179.9560546875
1158 * Default Value: 0
1159 * Units: deg
1160 *
1161 * Default Rates:
1162 * CAN: 100.0 Hz
1163 *
1164 * \returns Roll Status Signal Object
1165 */
1167
1168 /**
1169 * \brief The W component of the reported Quaternion.
1170 *
1171 * Minimum Value: -1.0001220852154804
1172 * Maximum Value: 1.0
1173 * Default Value: 0
1174 * Units:
1175 *
1176 * Default Rates:
1177 * CAN 2.0: 50.0 Hz
1178 * CAN FD: 100.0 Hz
1179 *
1180 * \returns QuatW Status Signal Object
1181 */
1183
1184 /**
1185 * \brief The X component of the reported Quaternion.
1186 *
1187 * Minimum Value: -1.0001220852154804
1188 * Maximum Value: 1.0
1189 * Default Value: 0
1190 * Units:
1191 *
1192 * Default Rates:
1193 * CAN 2.0: 50.0 Hz
1194 * CAN FD: 100.0 Hz
1195 *
1196 * \returns QuatX Status Signal Object
1197 */
1199
1200 /**
1201 * \brief The Y component of the reported Quaternion.
1202 *
1203 * Minimum Value: -1.0001220852154804
1204 * Maximum Value: 1.0
1205 * Default Value: 0
1206 * Units:
1207 *
1208 * Default Rates:
1209 * CAN 2.0: 50.0 Hz
1210 * CAN FD: 100.0 Hz
1211 *
1212 * \returns QuatY Status Signal Object
1213 */
1215
1216 /**
1217 * \brief The Z component of the reported Quaternion.
1218 *
1219 * Minimum Value: -1.0001220852154804
1220 * Maximum Value: 1.0
1221 * Default Value: 0
1222 * Units:
1223 *
1224 * Default Rates:
1225 * CAN 2.0: 50.0 Hz
1226 * CAN FD: 100.0 Hz
1227 *
1228 * \returns QuatZ Status Signal Object
1229 */
1231
1232 /**
1233 * \brief The X component of the gravity vector.
1234 *
1235 * \details This is the X component of the reported gravity-vector.
1236 * The gravity vector is not the acceleration experienced by the
1237 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1238 * can be used for mechanisms that are linearly related to gravity,
1239 * such as an arm pivoting about a point, as the contribution of
1240 * gravity to the arm is directly proportional to the contribution of
1241 * gravity about one of these primary axis.
1242 *
1243 * Minimum Value: -1.000030518509476
1244 * Maximum Value: 1.0
1245 * Default Value: 0
1246 * Units:
1247 *
1248 * Default Rates:
1249 * CAN 2.0: 10.0 Hz
1250 * CAN FD: 100.0 Hz
1251 *
1252 * \returns GravityVectorX Status Signal Object
1253 */
1255
1256 /**
1257 * \brief The Y component of the gravity vector.
1258 *
1259 * \details This is the X component of the reported gravity-vector.
1260 * The gravity vector is not the acceleration experienced by the
1261 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1262 * can be used for mechanisms that are linearly related to gravity,
1263 * such as an arm pivoting about a point, as the contribution of
1264 * gravity to the arm is directly proportional to the contribution of
1265 * gravity about one of these primary axis.
1266 *
1267 * Minimum Value: -1.000030518509476
1268 * Maximum Value: 1.0
1269 * Default Value: 0
1270 * Units:
1271 *
1272 * Default Rates:
1273 * CAN 2.0: 10.0 Hz
1274 * CAN FD: 100.0 Hz
1275 *
1276 * \returns GravityVectorY Status Signal Object
1277 */
1279
1280 /**
1281 * \brief The Z component of the gravity vector.
1282 *
1283 * \details This is the Z component of the reported gravity-vector.
1284 * The gravity vector is not the acceleration experienced by the
1285 * Pigeon2, rather it is where the Pigeon2 believes "Down" is. This
1286 * can be used for mechanisms that are linearly related to gravity,
1287 * such as an arm pivoting about a point, as the contribution of
1288 * gravity to the arm is directly proportional to the contribution of
1289 * gravity about one of these primary axis.
1290 *
1291 * Minimum Value: -1.000030518509476
1292 * Maximum Value: 1.0
1293 * Default Value: 0
1294 * Units:
1295 *
1296 * Default Rates:
1297 * CAN 2.0: 10.0 Hz
1298 * CAN FD: 100.0 Hz
1299 *
1300 * \returns GravityVectorZ Status Signal Object
1301 */
1303
1304 /**
1305 * \brief Temperature of the Pigeon 2.
1306 *
1307 * Minimum Value: -128.0
1308 * Maximum Value: 127.99609375
1309 * Default Value: 0
1310 * Units: ℃
1311 *
1312 * Default Rates:
1313 * CAN 2.0: 4.0 Hz
1314 * CAN FD: 100.0 Hz
1315 *
1316 * \returns Temperature Status Signal Object
1317 */
1319
1320 /**
1321 * \brief Whether the no-motion calibration feature is enabled.
1322 *
1323 * Default Value: 0
1324 *
1325 * Default Rates:
1326 * CAN 2.0: 4.0 Hz
1327 * CAN FD: 100.0 Hz
1328 *
1329 * \returns NoMotionEnabled Status Signal Object
1330 */
1332
1333 /**
1334 * \brief The number of times a no-motion event occurred, wraps at 15.
1335 *
1336 * Minimum Value: 0
1337 * Maximum Value: 15
1338 * Default Value: 0
1339 * Units:
1340 *
1341 * Default Rates:
1342 * CAN 2.0: 4.0 Hz
1343 * CAN FD: 100.0 Hz
1344 *
1345 * \returns NoMotionCount Status Signal Object
1346 */
1348
1349 /**
1350 * \brief Whether the temperature-compensation feature is disabled.
1351 *
1352 * Default Value: 0
1353 *
1354 * Default Rates:
1355 * CAN 2.0: 4.0 Hz
1356 * CAN FD: 100.0 Hz
1357 *
1358 * \returns TemperatureCompensationDisabled Status Signal Object
1359 */
1361
1362 /**
1363 * \brief How long the Pigeon 2's been up in seconds, caps at 255
1364 * seconds.
1365 *
1366 * Minimum Value: 0
1367 * Maximum Value: 255
1368 * Default Value: 0
1369 * Units: s
1370 *
1371 * Default Rates:
1372 * CAN 2.0: 4.0 Hz
1373 * CAN FD: 100.0 Hz
1374 *
1375 * \returns UpTime Status Signal Object
1376 */
1378
1379 /**
1380 * \brief The accumulated gyro about the X axis without any sensor
1381 * fusing.
1382 *
1383 * Minimum Value: -23040.0
1384 * Maximum Value: 23039.9560546875
1385 * Default Value: 0
1386 * Units: deg
1387 *
1388 * Default Rates:
1389 * CAN 2.0: 4.0 Hz
1390 * CAN FD: 100.0 Hz
1391 *
1392 * \returns AccumGyroX Status Signal Object
1393 */
1395
1396 /**
1397 * \brief The accumulated gyro about the Y axis without any sensor
1398 * fusing.
1399 *
1400 * Minimum Value: -23040.0
1401 * Maximum Value: 23039.9560546875
1402 * Default Value: 0
1403 * Units: deg
1404 *
1405 * Default Rates:
1406 * CAN 2.0: 4.0 Hz
1407 * CAN FD: 100.0 Hz
1408 *
1409 * \returns AccumGyroY Status Signal Object
1410 */
1412
1413 /**
1414 * \brief The accumulated gyro about the Z axis without any sensor
1415 * fusing.
1416 *
1417 * Minimum Value: -23040.0
1418 * Maximum Value: 23039.9560546875
1419 * Default Value: 0
1420 * Units: deg
1421 *
1422 * Default Rates:
1423 * CAN 2.0: 4.0 Hz
1424 * CAN FD: 100.0 Hz
1425 *
1426 * \returns AccumGyroZ Status Signal Object
1427 */
1429
1430 /**
1431 * \brief The angular velocity (ω) of the Pigeon 2 about the X axis.
1432 *
1433 * Minimum Value: -1998.048780487805
1434 * Maximum Value: 1997.987804878049
1435 * Default Value: 0
1436 * Units: dps
1437 *
1438 * Default Rates:
1439 * CAN 2.0: 10.0 Hz
1440 * CAN FD: 100.0 Hz
1441 *
1442 * \returns AngularVelocityX Status Signal Object
1443 */
1445
1446 /**
1447 * \brief The angular velocity (ω) of the Pigeon 2 about the Y axis.
1448 *
1449 * Minimum Value: -1998.048780487805
1450 * Maximum Value: 1997.987804878049
1451 * Default Value: 0
1452 * Units: dps
1453 *
1454 * Default Rates:
1455 * CAN 2.0: 10.0 Hz
1456 * CAN FD: 100.0 Hz
1457 *
1458 * \returns AngularVelocityY Status Signal Object
1459 */
1461
1462 /**
1463 * \brief The angular velocity (ω) of the Pigeon 2 about the Z axis.
1464 *
1465 * Minimum Value: -1998.048780487805
1466 * Maximum Value: 1997.987804878049
1467 * Default Value: 0
1468 * Units: dps
1469 *
1470 * Default Rates:
1471 * CAN 2.0: 10.0 Hz
1472 * CAN FD: 100.0 Hz
1473 *
1474 * \returns AngularVelocityZ Status Signal Object
1475 */
1477
1478 /**
1479 * \brief The acceleration measured by Pigeon2 in the X direction.
1480 *
1481 * \details This value includes the acceleration due to gravity. If
1482 * this is undesirable, get the gravity vector and subtract out the
1483 * contribution in this direction.
1484 *
1485 * Minimum Value: -2.0
1486 * Maximum Value: 1.99993896484375
1487 * Default Value: 0
1488 * Units: g
1489 *
1490 * Default Rates:
1491 * CAN 2.0: 10.0 Hz
1492 * CAN FD: 100.0 Hz
1493 *
1494 * \returns AccelerationX Status Signal Object
1495 */
1497
1498 /**
1499 * \brief The acceleration measured by Pigeon2 in the Y direction.
1500 *
1501 * \details This value includes the acceleration due to gravity. If
1502 * this is undesirable, get the gravity vector and subtract out the
1503 * contribution in this direction.
1504 *
1505 * Minimum Value: -2.0
1506 * Maximum Value: 1.99993896484375
1507 * Default Value: 0
1508 * Units: g
1509 *
1510 * Default Rates:
1511 * CAN 2.0: 10.0 Hz
1512 * CAN FD: 100.0 Hz
1513 *
1514 * \returns AccelerationY Status Signal Object
1515 */
1517
1518 /**
1519 * \brief The acceleration measured by Pigeon2 in the Z direction.
1520 *
1521 * \details This value includes the acceleration due to gravity. If
1522 * this is undesirable, get the gravity vector and subtract out the
1523 * contribution in this direction.
1524 *
1525 * Minimum Value: -2.0
1526 * Maximum Value: 1.99993896484375
1527 * Default Value: 0
1528 * Units: g
1529 *
1530 * Default Rates:
1531 * CAN 2.0: 10.0 Hz
1532 * CAN FD: 100.0 Hz
1533 *
1534 * \returns AccelerationZ Status Signal Object
1535 */
1537
1538 /**
1539 * \brief Measured supply voltage to the Pigeon2.
1540 *
1541 * Minimum Value: 0.0
1542 * Maximum Value: 31.99951171875
1543 * Default Value: 0
1544 * Units: V
1545 *
1546 * Default Rates:
1547 * CAN 2.0: 4.0 Hz
1548 * CAN FD: 100.0 Hz
1549 *
1550 * \returns SupplyVoltage Status Signal Object
1551 */
1553
1554 /**
1555 * \brief The biased magnitude of the magnetic field measured by the
1556 * Pigeon 2 in the X direction. This is only valid after performing a
1557 * magnetometer calibration.
1558 *
1559 * Minimum Value: -19660.8
1560 * Maximum Value: 19660.2
1561 * Default Value: 0
1562 * Units: uT
1563 *
1564 * Default Rates:
1565 * CAN: 4.0 Hz
1566 *
1567 * \returns MagneticFieldX Status Signal Object
1568 */
1570
1571 /**
1572 * \brief The biased magnitude of the magnetic field measured by the
1573 * Pigeon 2 in the Y direction. This is only valid after performing a
1574 * magnetometer calibration.
1575 *
1576 * Minimum Value: -19660.8
1577 * Maximum Value: 19660.2
1578 * Default Value: 0
1579 * Units: uT
1580 *
1581 * Default Rates:
1582 * CAN: 4.0 Hz
1583 *
1584 * \returns MagneticFieldY Status Signal Object
1585 */
1587
1588 /**
1589 * \brief The biased magnitude of the magnetic field measured by the
1590 * Pigeon 2 in the Z direction. This is only valid after performing a
1591 * magnetometer calibration.
1592 *
1593 * Minimum Value: -19660.8
1594 * Maximum Value: 19660.2
1595 * Default Value: 0
1596 * Units: uT
1597 *
1598 * Default Rates:
1599 * CAN: 4.0 Hz
1600 *
1601 * \returns MagneticFieldZ Status Signal Object
1602 */
1604
1605 /**
1606 * \brief The raw magnitude of the magnetic field measured by the
1607 * Pigeon 2 in the X direction. This is only valid after performing a
1608 * magnetometer calibration.
1609 *
1610 * Minimum Value: -19660.8
1611 * Maximum Value: 19660.2
1612 * Default Value: 0
1613 * Units: uT
1614 *
1615 * Default Rates:
1616 * CAN: 4.0 Hz
1617 *
1618 * \returns RawMagneticFieldX Status Signal Object
1619 */
1621
1622 /**
1623 * \brief The raw magnitude of the magnetic field measured by the
1624 * Pigeon 2 in the Y direction. This is only valid after performing a
1625 * magnetometer calibration.
1626 *
1627 * Minimum Value: -19660.8
1628 * Maximum Value: 19660.2
1629 * Default Value: 0
1630 * Units: uT
1631 *
1632 * Default Rates:
1633 * CAN: 4.0 Hz
1634 *
1635 * \returns RawMagneticFieldY Status Signal Object
1636 */
1638
1639 /**
1640 * \brief The raw magnitude of the magnetic field measured by the
1641 * Pigeon 2 in the Z direction. This is only valid after performing a
1642 * magnetometer calibration.
1643 *
1644 * Minimum Value: -19660.8
1645 * Maximum Value: 19660.2
1646 * Default Value: 0
1647 * Units: uT
1648 *
1649 * Default Rates:
1650 * CAN: 4.0 Hz
1651 *
1652 * \returns RawMagneticFieldZ Status Signal Object
1653 */
1655
1656 /**
1657 * \brief Whether the device is Phoenix Pro licensed.
1658 *
1659 * Default Value: False
1660 *
1661 * Default Rates:
1662 * CAN: 4.0 Hz
1663 *
1664 * \returns IsProLicensed Status Signal Object
1665 */
1667
1668 /**
1669 * \brief Hardware fault occurred
1670 *
1671 * Default Value: False
1672 *
1673 * Default Rates:
1674 * CAN: 4.0 Hz
1675 *
1676 * \returns Fault_Hardware Status Signal Object
1677 */
1679
1680 /**
1681 * \brief Hardware fault occurred
1682 *
1683 * Default Value: False
1684 *
1685 * Default Rates:
1686 * CAN: 4.0 Hz
1687 *
1688 * \returns StickyFault_Hardware Status Signal Object
1689 */
1691
1692 /**
1693 * \brief Device supply voltage dropped to near brownout levels
1694 *
1695 * Default Value: False
1696 *
1697 * Default Rates:
1698 * CAN: 4.0 Hz
1699 *
1700 * \returns Fault_Undervoltage Status Signal Object
1701 */
1703
1704 /**
1705 * \brief Device supply voltage dropped to near brownout levels
1706 *
1707 * Default Value: False
1708 *
1709 * Default Rates:
1710 * CAN: 4.0 Hz
1711 *
1712 * \returns StickyFault_Undervoltage Status Signal Object
1713 */
1715
1716 /**
1717 * \brief Device boot while detecting the enable signal
1718 *
1719 * Default Value: False
1720 *
1721 * Default Rates:
1722 * CAN: 4.0 Hz
1723 *
1724 * \returns Fault_BootDuringEnable Status Signal Object
1725 */
1727
1728 /**
1729 * \brief Device boot while detecting the enable signal
1730 *
1731 * Default Value: False
1732 *
1733 * Default Rates:
1734 * CAN: 4.0 Hz
1735 *
1736 * \returns StickyFault_BootDuringEnable Status Signal Object
1737 */
1739
1740 /**
1741 * \brief An unlicensed feature is in use, device may not behave as
1742 * expected.
1743 *
1744 * Default Value: False
1745 *
1746 * Default Rates:
1747 * CAN: 4.0 Hz
1748 *
1749 * \returns Fault_UnlicensedFeatureInUse Status Signal Object
1750 */
1752
1753 /**
1754 * \brief An unlicensed feature is in use, device may not behave as
1755 * expected.
1756 *
1757 * Default Value: False
1758 *
1759 * Default Rates:
1760 * CAN: 4.0 Hz
1761 *
1762 * \returns StickyFault_UnlicensedFeatureInUse Status Signal Object
1763 */
1765
1766 /**
1767 * \brief Bootup checks failed: Accelerometer
1768 *
1769 * Default Value: False
1770 *
1771 * Default Rates:
1772 * CAN: 4.0 Hz
1773 *
1774 * \returns Fault_BootupAccelerometer Status Signal Object
1775 */
1777
1778 /**
1779 * \brief Bootup checks failed: Accelerometer
1780 *
1781 * Default Value: False
1782 *
1783 * Default Rates:
1784 * CAN: 4.0 Hz
1785 *
1786 * \returns StickyFault_BootupAccelerometer Status Signal Object
1787 */
1789
1790 /**
1791 * \brief Bootup checks failed: Gyroscope
1792 *
1793 * Default Value: False
1794 *
1795 * Default Rates:
1796 * CAN: 4.0 Hz
1797 *
1798 * \returns Fault_BootupGyroscope Status Signal Object
1799 */
1801
1802 /**
1803 * \brief Bootup checks failed: Gyroscope
1804 *
1805 * Default Value: False
1806 *
1807 * Default Rates:
1808 * CAN: 4.0 Hz
1809 *
1810 * \returns StickyFault_BootupGyroscope Status Signal Object
1811 */
1813
1814 /**
1815 * \brief Bootup checks failed: Magnetometer
1816 *
1817 * Default Value: False
1818 *
1819 * Default Rates:
1820 * CAN: 4.0 Hz
1821 *
1822 * \returns Fault_BootupMagnetometer Status Signal Object
1823 */
1825
1826 /**
1827 * \brief Bootup checks failed: Magnetometer
1828 *
1829 * Default Value: False
1830 *
1831 * Default Rates:
1832 * CAN: 4.0 Hz
1833 *
1834 * \returns StickyFault_BootupMagnetometer Status Signal Object
1835 */
1837
1838 /**
1839 * \brief Motion Detected during bootup.
1840 *
1841 * Default Value: False
1842 *
1843 * Default Rates:
1844 * CAN: 4.0 Hz
1845 *
1846 * \returns Fault_BootIntoMotion Status Signal Object
1847 */
1849
1850 /**
1851 * \brief Motion Detected during bootup.
1852 *
1853 * Default Value: False
1854 *
1855 * Default Rates:
1856 * CAN: 4.0 Hz
1857 *
1858 * \returns StickyFault_BootIntoMotion Status Signal Object
1859 */
1861
1862 /**
1863 * \brief Motion stack data acquisition was slower than expected
1864 *
1865 * Default Value: False
1866 *
1867 * Default Rates:
1868 * CAN: 4.0 Hz
1869 *
1870 * \returns Fault_DataAcquiredLate Status Signal Object
1871 */
1873
1874 /**
1875 * \brief Motion stack data acquisition was slower than expected
1876 *
1877 * Default Value: False
1878 *
1879 * Default Rates:
1880 * CAN: 4.0 Hz
1881 *
1882 * \returns StickyFault_DataAcquiredLate Status Signal Object
1883 */
1885
1886 /**
1887 * \brief Motion stack loop time was slower than expected.
1888 *
1889 * Default Value: False
1890 *
1891 * Default Rates:
1892 * CAN: 4.0 Hz
1893 *
1894 * \returns Fault_LoopTimeSlow Status Signal Object
1895 */
1897
1898 /**
1899 * \brief Motion stack loop time was slower than expected.
1900 *
1901 * Default Value: False
1902 *
1903 * Default Rates:
1904 * CAN: 4.0 Hz
1905 *
1906 * \returns StickyFault_LoopTimeSlow Status Signal Object
1907 */
1909
1910 /**
1911 * \brief Magnetometer values are saturated
1912 *
1913 * Default Value: False
1914 *
1915 * Default Rates:
1916 * CAN: 4.0 Hz
1917 *
1918 * \returns Fault_SaturatedMagnetometer Status Signal Object
1919 */
1921
1922 /**
1923 * \brief Magnetometer values are saturated
1924 *
1925 * Default Value: False
1926 *
1927 * Default Rates:
1928 * CAN: 4.0 Hz
1929 *
1930 * \returns StickyFault_SaturatedMagnetometer Status Signal Object
1931 */
1933
1934 /**
1935 * \brief Accelerometer values are saturated
1936 *
1937 * Default Value: False
1938 *
1939 * Default Rates:
1940 * CAN: 4.0 Hz
1941 *
1942 * \returns Fault_SaturatedAccelometer Status Signal Object
1943 */
1945
1946 /**
1947 * \brief Accelerometer values are saturated
1948 *
1949 * Default Value: False
1950 *
1951 * Default Rates:
1952 * CAN: 4.0 Hz
1953 *
1954 * \returns StickyFault_SaturatedAccelometer Status Signal Object
1955 */
1957
1958 /**
1959 * \brief Gyroscope values are saturated
1960 *
1961 * Default Value: False
1962 *
1963 * Default Rates:
1964 * CAN: 4.0 Hz
1965 *
1966 * \returns Fault_SaturatedGyroscope Status Signal Object
1967 */
1969
1970 /**
1971 * \brief Gyroscope values are saturated
1972 *
1973 * Default Value: False
1974 *
1975 * Default Rates:
1976 * CAN: 4.0 Hz
1977 *
1978 * \returns StickyFault_SaturatedGyroscope Status Signal Object
1979 */
1981
1982
1983
1984 /**
1985 * \brief Control motor with generic control request object. User must make
1986 * sure the specified object is castable to a valid control request,
1987 * otherwise this function will fail at run-time and return the NotSupported
1988 * StatusCode
1989 *
1990 * \param request Control object to request of the device
1991 * \returns Status Code of the request, 0 is OK
1992 */
1993 ctre::phoenix::StatusCode SetControl(controls::ControlRequest& request)
1994 {
1995 controls::ControlRequest *ptr = &request;
1996 (void)ptr;
1997
1999 }
2000 /**
2001 * \brief Control motor with generic control request object. User must make
2002 * sure the specified object is castable to a valid control request,
2003 * otherwise this function will fail at run-time and return the corresponding
2004 * StatusCode
2005 *
2006 * \param request Control object to request of the device
2007 * \returns Status Code of the request, 0 is OK
2008 */
2009 ctre::phoenix::StatusCode SetControl(controls::ControlRequest&& request)
2010 {
2011 return SetControl(request);
2012 }
2013
2014
2015 /**
2016 * \brief The yaw to set the Pigeon2 to right now.
2017 *
2018 * \param newValue Value to set to. Units are in deg.
2019 * \param timeoutSeconds Maximum time to wait up to in seconds.
2020 * \returns StatusCode of the set command
2021 */
2022 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
2023 {
2024 return GetConfigurator().SetYaw(newValue, timeoutSeconds);
2025 }
2026 /**
2027 * \brief The yaw to set the Pigeon2 to right now.
2028 *
2029 * This will wait up to 0.050 seconds (50ms) by default.
2030 *
2031 * \param newValue Value to set to. Units are in deg.
2032 * \returns StatusCode of the set command
2033 */
2034 ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
2035 {
2036 return SetYaw(newValue, 0.050_s);
2037 }
2038
2039 /**
2040 * \brief Clear the sticky faults in the device.
2041 *
2042 * \details This typically has no impact on the device functionality.
2043 * Instead, it just clears telemetry faults that are accessible via
2044 * API and Tuner Self-Test.
2045 * \param timeoutSeconds Maximum time to wait up to in seconds.
2046 * \returns StatusCode of the set command
2047 */
2048 ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
2049 {
2050 return GetConfigurator().ClearStickyFaults(timeoutSeconds);
2051 }
2052 /**
2053 * \brief Clear the sticky faults in the device.
2054 *
2055 * \details This typically has no impact on the device functionality.
2056 * Instead, it just clears telemetry faults that are accessible via
2057 * API and Tuner Self-Test.
2058 *
2059 * This will wait up to 0.050 seconds (50ms) by default.
2060 * \returns StatusCode of the set command
2061 */
2062 ctre::phoenix::StatusCode ClearStickyFaults()
2063 {
2064 return ClearStickyFaults(0.050_s);
2065 }
2066
2067 /**
2068 * \brief Clear sticky fault: Hardware fault occurred
2069 * \param timeoutSeconds Maximum time to wait up to in seconds.
2070 * \returns StatusCode of the set command
2071 */
2072 ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
2073 {
2074 return GetConfigurator().ClearStickyFault_Hardware(timeoutSeconds);
2075 }
2076 /**
2077 * \brief Clear sticky fault: Hardware fault occurred
2078 *
2079 * This will wait up to 0.050 seconds (50ms) by default.
2080 * \returns StatusCode of the set command
2081 */
2082 ctre::phoenix::StatusCode ClearStickyFault_Hardware()
2083 {
2084 return ClearStickyFault_Hardware(0.050_s);
2085 }
2086
2087 /**
2088 * \brief Clear sticky fault: Device supply voltage dropped to near
2089 * brownout levels
2090 * \param timeoutSeconds Maximum time to wait up to in seconds.
2091 * \returns StatusCode of the set command
2092 */
2093 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
2094 {
2095 return GetConfigurator().ClearStickyFault_Undervoltage(timeoutSeconds);
2096 }
2097 /**
2098 * \brief Clear sticky fault: Device supply voltage dropped to near
2099 * brownout levels
2100 *
2101 * This will wait up to 0.050 seconds (50ms) by default.
2102 * \returns StatusCode of the set command
2103 */
2104 ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
2105 {
2106 return ClearStickyFault_Undervoltage(0.050_s);
2107 }
2108
2109 /**
2110 * \brief Clear sticky fault: Device boot while detecting the enable
2111 * signal
2112 * \param timeoutSeconds Maximum time to wait up to in seconds.
2113 * \returns StatusCode of the set command
2114 */
2115 ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
2116 {
2117 return GetConfigurator().ClearStickyFault_BootDuringEnable(timeoutSeconds);
2118 }
2119 /**
2120 * \brief Clear sticky fault: Device boot while detecting the enable
2121 * signal
2122 *
2123 * This will wait up to 0.050 seconds (50ms) by default.
2124 * \returns StatusCode of the set command
2125 */
2126 ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
2127 {
2128 return ClearStickyFault_BootDuringEnable(0.050_s);
2129 }
2130
2131 /**
2132 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2133 * \param timeoutSeconds Maximum time to wait up to in seconds.
2134 * \returns StatusCode of the set command
2135 */
2136 ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
2137 {
2139 }
2140 /**
2141 * \brief Clear sticky fault: Bootup checks failed: Accelerometer
2142 *
2143 * This will wait up to 0.050 seconds (50ms) by default.
2144 * \returns StatusCode of the set command
2145 */
2146 ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
2147 {
2149 }
2150
2151 /**
2152 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2153 * \param timeoutSeconds Maximum time to wait up to in seconds.
2154 * \returns StatusCode of the set command
2155 */
2156 ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
2157 {
2158 return GetConfigurator().ClearStickyFault_BootupGyroscope(timeoutSeconds);
2159 }
2160 /**
2161 * \brief Clear sticky fault: Bootup checks failed: Gyroscope
2162 *
2163 * This will wait up to 0.050 seconds (50ms) by default.
2164 * \returns StatusCode of the set command
2165 */
2166 ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
2167 {
2168 return ClearStickyFault_BootupGyroscope(0.050_s);
2169 }
2170
2171 /**
2172 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2173 * \param timeoutSeconds Maximum time to wait up to in seconds.
2174 * \returns StatusCode of the set command
2175 */
2176 ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
2177 {
2179 }
2180 /**
2181 * \brief Clear sticky fault: Bootup checks failed: Magnetometer
2182 *
2183 * This will wait up to 0.050 seconds (50ms) by default.
2184 * \returns StatusCode of the set command
2185 */
2186 ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
2187 {
2189 }
2190
2191 /**
2192 * \brief Clear sticky fault: Motion Detected during bootup.
2193 * \param timeoutSeconds Maximum time to wait up to in seconds.
2194 * \returns StatusCode of the set command
2195 */
2196 ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
2197 {
2198 return GetConfigurator().ClearStickyFault_BootIntoMotion(timeoutSeconds);
2199 }
2200 /**
2201 * \brief Clear sticky fault: Motion Detected during bootup.
2202 *
2203 * This will wait up to 0.050 seconds (50ms) by default.
2204 * \returns StatusCode of the set command
2205 */
2206 ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
2207 {
2208 return ClearStickyFault_BootIntoMotion(0.050_s);
2209 }
2210
2211 /**
2212 * \brief Clear sticky fault: Motion stack data acquisition was slower
2213 * than expected
2214 * \param timeoutSeconds Maximum time to wait up to in seconds.
2215 * \returns StatusCode of the set command
2216 */
2217 ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
2218 {
2219 return GetConfigurator().ClearStickyFault_DataAcquiredLate(timeoutSeconds);
2220 }
2221 /**
2222 * \brief Clear sticky fault: Motion stack data acquisition was slower
2223 * than expected
2224 *
2225 * This will wait up to 0.050 seconds (50ms) by default.
2226 * \returns StatusCode of the set command
2227 */
2228 ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
2229 {
2230 return ClearStickyFault_DataAcquiredLate(0.050_s);
2231 }
2232
2233 /**
2234 * \brief Clear sticky fault: Motion stack loop time was slower than
2235 * expected.
2236 * \param timeoutSeconds Maximum time to wait up to in seconds.
2237 * \returns StatusCode of the set command
2238 */
2239 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
2240 {
2241 return GetConfigurator().ClearStickyFault_LoopTimeSlow(timeoutSeconds);
2242 }
2243 /**
2244 * \brief Clear sticky fault: Motion stack loop time was slower than
2245 * expected.
2246 *
2247 * This will wait up to 0.050 seconds (50ms) by default.
2248 * \returns StatusCode of the set command
2249 */
2250 ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
2251 {
2252 return ClearStickyFault_LoopTimeSlow(0.050_s);
2253 }
2254
2255 /**
2256 * \brief Clear sticky fault: Magnetometer values are saturated
2257 * \param timeoutSeconds Maximum time to wait up to in seconds.
2258 * \returns StatusCode of the set command
2259 */
2260 ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
2261 {
2263 }
2264 /**
2265 * \brief Clear sticky fault: Magnetometer values are saturated
2266 *
2267 * This will wait up to 0.050 seconds (50ms) by default.
2268 * \returns StatusCode of the set command
2269 */
2270 ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
2271 {
2273 }
2274
2275 /**
2276 * \brief Clear sticky fault: Accelerometer values are saturated
2277 * \param timeoutSeconds Maximum time to wait up to in seconds.
2278 * \returns StatusCode of the set command
2279 */
2280 ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer(units::time::second_t timeoutSeconds)
2281 {
2283 }
2284 /**
2285 * \brief Clear sticky fault: Accelerometer values are saturated
2286 *
2287 * This will wait up to 0.050 seconds (50ms) by default.
2288 * \returns StatusCode of the set command
2289 */
2290 ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer()
2291 {
2293 }
2294
2295 /**
2296 * \brief Clear sticky fault: Gyroscope values are saturated
2297 * \param timeoutSeconds Maximum time to wait up to in seconds.
2298 * \returns StatusCode of the set command
2299 */
2300 ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
2301 {
2303 }
2304 /**
2305 * \brief Clear sticky fault: Gyroscope values are saturated
2306 *
2307 * This will wait up to 0.050 seconds (50ms) by default.
2308 * \returns StatusCode of the set command
2309 */
2310 ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
2311 {
2313 }
2314};
2315
2316}
2317}
2318
2319}
2320}
2321
ii that the Software will be uninterrupted or error free
Definition: CTRE_LICENSE.txt:191
CTREXPORT int c_ctre_phoenix6_serialize_double(int spn, double value, char **str)
@ OK
No Error.
Definition: StatusCodes.h:1169
@ NotSupported
This is not supported.
Definition: StatusCodes.h:1780
bool HasUpdated()
Check whether the signal has been updated since the last check.
Definition: StatusSignal.hpp:577
StatusSignal< T > & Refresh(bool ReportOnError=true)
Refreshes the value of this status signal.
Definition: StatusSignal.hpp:821
Configs to trim the Pigeon2's gyroscope.
Definition: Configs.hpp:193
std::string Serialize() const override
Definition: Configs.hpp:237
std::string ToString() const override
Definition: Configs.hpp:225
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition: Configs.hpp:247
Configs for Pigeon 2's Mount Pose configuration.
Definition: Configs.hpp:117
std::string ToString() const override
Definition: Configs.hpp:149
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition: Configs.hpp:171
std::string Serialize() const override
Definition: Configs.hpp:161
Definition: Configurator.hpp:21
units::time::second_t defaultTimeoutSeconds
The default amount of time to wait for a config.
Definition: Configurator.hpp:26
ctre::phoenix::StatusCode SetConfigsPrivate(const std::string &serializedString, units::time::second_t timeoutSeconds, bool futureProofConfigs, bool overrideIfDuplicate)
Definition: Configurator.hpp:37
ctre::phoenix::StatusCode GetConfigsPrivate(std::string &serializedString, units::time::second_t timeoutSeconds) const
Definition: Configurator.hpp:61
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:40
Pigeon2FeaturesConfigs Pigeon2Features
Configs to enable/disable various features of the Pigeon2.
Definition: CorePigeon2.hpp:84
GyroTrimConfigs GyroTrim
Configs to trim the Pigeon2's gyroscope.
Definition: CorePigeon2.hpp:76
std::string ToString() const
Get the string representation of this configuration.
Definition: CorePigeon2.hpp:89
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize)
Take a string and deserialize it to this configuration.
Definition: CorePigeon2.hpp:113
bool FutureProofConfigs
True if we should factory default newer unsupported configs, false to leave newer unsupported configs...
Definition: CorePigeon2.hpp:55
MountPoseConfigs MountPose
Configs for Pigeon 2's Mount Pose configuration.
Definition: CorePigeon2.hpp:65
std::string Serialize() const
Get the serialized form of this configuration.
Definition: CorePigeon2.hpp:101
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:129
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:552
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:347
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:245
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:766
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:658
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:887
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:198
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:416
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:638
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:708
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:494
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:334
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:399
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:531
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:379
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:745
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:515
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:673
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:693
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:184
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:214
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:365
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:319
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:802
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:588
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:459
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:287
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:852
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:817
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:227
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:274
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:872
Pigeon2Configurator(const Pigeon2Configurator &)=delete
Delete the copy constructor, we can only pass by reference.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:568
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:603
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:623
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:166
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer()
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:837
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:782
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:440
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:259
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:152
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:729
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:305
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:479
Configs to enable/disable various features of the Pigeon2.
Definition: Configs.hpp:266
std::string ToString() const override
Definition: Configs.hpp:292
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition: Configs.hpp:314
std::string Serialize() const override
Definition: Configs.hpp:304
Abstract Control Request class that other control requests extend for use.
Definition: ControlRequest.hpp:28
Definition: DeviceIdentifier.hpp:19
Parent class for all devices.
Definition: ParentDevice.hpp:30
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:905
StatusSignal< bool > & GetFault_BootIntoMotion()
Motion Detected during bootup.
StatusSignal< int > & GetVersionMinor()
App Minor Version number.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZ()
The angular velocity (ω) of the Pigeon 2 about the Z axis.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:2104
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:2176
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldZ()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
StatusSignal< units::angle::degree_t > & GetPitch()
Current reported pitch of the Pigeon2.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:2146
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:2217
StatusSignal< int > & GetVersion()
Full Version.
StatusSignal< units::angle::degree_t > & GetAccumGyroX()
The accumulated gyro about the X axis without any sensor fusing.
CorePigeon2(CorePigeon2 const &)=delete
StatusSignal< units::dimensionless::scalar_t > & GetNoMotionCount()
The number of times a no-motion event occurred, wraps at 15.
StatusSignal< units::angle::degree_t > & GetRoll()
Current reported roll of the Pigeon2.
CorePigeon2 & operator=(CorePigeon2 const &)=delete
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldY()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
std::function< bool()> GetResetOccurredChecker() const
Definition: CorePigeon2.hpp:952
StatusSignal< int > & GetVersionBugfix()
App Bugfix Version number.
StatusSignal< bool > & GetStickyFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:2062
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:2239
StatusSignal< bool > & GetStickyFault_Hardware()
Hardware fault occurred.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldY()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
StatusSignal< bool > & GetFault_BootupMagnetometer()
Bootup checks failed: Magnetometer.
StatusSignal< units::temperature::celsius_t > & GetTemperature()
Temperature of the Pigeon 2.
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:2228
StatusSignal< bool > & GetStickyFault_BootDuringEnable()
Device boot while detecting the enable signal.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldX()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignal< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
ctre::phoenix::StatusCode SetControl(controls::ControlRequest &request)
Control motor with generic control request object.
Definition: CorePigeon2.hpp:1993
StatusSignal< units::dimensionless::scalar_t > & GetQuatX()
The X component of the reported Quaternion.
StatusSignal< units::angle::degree_t > & GetAccumGyroZ()
The accumulated gyro about the Z axis without any sensor fusing.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorX()
The X component of the gravity vector.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:2310
StatusSignal< bool > & GetStickyFault_LoopTimeSlow()
Motion stack loop time was slower than expected.
configs::Pigeon2Configurator & GetConfigurator()
Gets the configurator for this Pigeon2.
Definition: CorePigeon2.hpp:966
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:2082
StatusSignal< bool > & GetFault_UnlicensedFeatureInUse()
An unlicensed feature is in use, device may not behave as expected.
StatusSignal< bool > & GetStickyFault_UnlicensedFeatureInUse()
An unlicensed feature is in use, device may not behave as expected.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:2022
configs::Pigeon2Configurator const & GetConfigurator() const
Gets the configurator for this Pigeon2.
Definition: CorePigeon2.hpp:978
StatusSignal< int > & GetVersionMajor()
App Major Version number.
StatusSignal< units::time::second_t > & GetUpTime()
How long the Pigeon 2's been up in seconds, caps at 255 seconds.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorZ()
The Z component of the gravity vector.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:2300
StatusSignal< units::voltage::volt_t > & GetSupplyVoltage()
Measured supply voltage to the Pigeon2.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityX()
The angular velocity (ω) of the Pigeon 2 about the X axis.
StatusSignal< units::dimensionless::scalar_t > & GetQuatW()
The W component of the reported Quaternion.
StatusSignal< bool > & GetStickyFault_SaturatedAccelometer()
Accelerometer values are saturated.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationY()
The acceleration measured by Pigeon2 in the Y direction.
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:2048
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:2260
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:2166
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldX()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY()
The Y component of the reported Quaternion.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:2206
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:2280
bool HasResetOccurred()
Definition: CorePigeon2.hpp:944
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:2270
StatusSignal< bool > & GetStickyFault_BootupMagnetometer()
Bootup checks failed: Magnetometer.
StatusSignal< bool > & GetFault_BootDuringEnable()
Device boot while detecting the enable signal.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:2115
StatusSignal< int > & GetFaultField()
Integer representing all faults.
StatusSignal< bool > & GetIsProLicensed()
Whether the device is Phoenix Pro licensed.
StatusSignal< bool > & GetStickyFault_BootupGyroscope()
Bootup checks failed: Gyroscope.
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:2250
ctre::phoenix::StatusCode SetControl(controls::ControlRequest &&request)
Control motor with generic control request object.
Definition: CorePigeon2.hpp:2009
StatusSignal< bool > & GetFault_SaturatedGyroscope()
Gyroscope values are saturated.
StatusSignal< bool > & GetFault_Undervoltage()
Device supply voltage dropped to near brownout levels.
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ()
The Z component of the reported Quaternion.
StatusSignal< bool > & GetFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected.
StatusSignal< int > & GetStickyFaultField()
Integer representing all sticky faults.
StatusSignal< bool > & GetStickyFault_BootIntoMotion()
Motion Detected during bootup.
StatusSignal< bool > & GetStickyFault_SaturatedMagnetometer()
Magnetometer values are saturated.
StatusSignal< bool > & GetStickyFault_Undervoltage()
Device supply voltage dropped to near brownout levels.
StatusSignal< bool > & GetFault_BootupAccelerometer()
Bootup checks failed: Accelerometer.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:2093
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:2156
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:2196
CorePigeon2(int deviceId, std::string canbus="")
Constructs a new Pigeon 2 sensor object.
StatusSignal< bool > & GetFault_SaturatedAccelometer()
Accelerometer values are saturated.
StatusSignal< bool > & GetFault_SaturatedMagnetometer()
Magnetometer values are saturated.
StatusSignal< bool > & GetNoMotionEnabled()
Whether the no-motion calibration feature is enabled.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldZ()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelometer()
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:2290
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:2072
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityY()
The angular velocity (ω) of the Pigeon 2 about the Y axis.
StatusSignal< bool > & GetTemperatureCompensationDisabled()
Whether the temperature-compensation feature is disabled.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:2034
StatusSignal< bool > & GetFault_BootupGyroscope()
Bootup checks failed: Gyroscope.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorY()
The Y component of the gravity vector.
StatusSignal< bool > & GetFault_Hardware()
Hardware fault occurred.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:2126
StatusSignal< bool > & GetStickyFault_SaturatedGyroscope()
Gyroscope values are saturated.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationZ()
The acceleration measured by Pigeon2 in the Z direction.
StatusSignal< int > & GetVersionBuild()
App Build Version number.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:2136
StatusSignal< bool > & GetFault_LoopTimeSlow()
Motion stack loop time was slower than expected.
StatusSignal< bool > & GetStickyFault_BootupAccelerometer()
Bootup checks failed: Accelerometer.
StatusSignal< units::angle::degree_t > & GetAccumGyroY()
The accumulated gyro about the Y axis without any sensor fusing.
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:2186
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationX()
The acceleration measured by Pigeon2 in the X direction.
sim::Pigeon2SimState & GetSimState()
Get the simulation state for this device.
Definition: CorePigeon2.hpp:996
Class to control the state of a simulated hardware::Pigeon2.
Definition: Pigeon2SimState.hpp:30
CTREXPORT double GetCurrentTimeSeconds()
Get the current timestamp in seconds.
Definition: ManualEvent.hpp:12